modules remove extra semicolons

This commit is contained in:
Daniel Agar 2017-06-04 12:48:50 -04:00 committed by Nuno Marques
parent 08fbd022af
commit 545ce9ae24
18 changed files with 48 additions and 46 deletions

View File

@ -186,8 +186,8 @@ protected:
} \
} while (0)
virtual void _init(void) { }; ///< Run before each unit test. Override to provide custom behavior.
virtual void _cleanup(void) { }; ///< Run after each unit test. Override to provide custom behavior.
virtual void _init(void) {} ///< Run before each unit test. Override to provide custom behavior.
virtual void _cleanup(void) {} ///< Run after each unit test. Override to provide custom behavior.
void _print_assert(const char *msg, const char *test, const char *file, int line)
{

View File

@ -101,7 +101,7 @@ public:
/** @see ModuleBase::run() */
void run() override;
void set_replay_mode(bool replay) {_replay_mode = replay;};
void set_replay_mode(bool replay) { _replay_mode = replay; }
static void task_main_trampoline(int argc, char *argv[]);

View File

@ -1014,7 +1014,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &curr_pos, cons
altitude_desired_rel = L_altitude_rel;
} else {
altitude_desired_rel = _global_pos.alt - terrain_alt;;
altitude_desired_rel = _global_pos.alt - terrain_alt;
}
}

View File

@ -59,9 +59,9 @@ public:
overrideThrottleMaxEnabled(false),
overridePitchMinEnabled(false),
overridePitchMaxEnabled(false)
{};
{}
~LimitOverride() {};
~LimitOverride() {}
/*
* Override the limits of the outputlimiter instances given by the arguments with the limits saved in

View File

@ -61,8 +61,8 @@ public:
_isAngularLimit(fAngularLimit),
_min(this, "MIN"),
_max(this, "MAX")
{};
virtual ~BlockOutputLimiter() {};
{}
virtual ~BlockOutputLimiter() {}
/*
* Imposes the limits given by _min and _max on value
*
@ -116,8 +116,8 @@ public:
_kP(this, "P"),
_kI(this, "I"),
_offset(this, "OFF")
{};
virtual ~BlockFFPILimited() {};
{}
virtual ~BlockFFPILimited() {}
float update(float inputValue, float inputError) { return calcLimitedOutput(inputValue, inputError, _outputLimiter); }
// accessors
BlockIntegral &getIntegral() { return _integral; }
@ -159,8 +159,8 @@ public:
// methods
BlockFFPILimitedCustom(SuperBlock *parent, const char *name, bool isAngularLimit = false) :
BlockFFPILimited(parent, name, isAngularLimit)
{};
virtual ~BlockFFPILimitedCustom() {};
{}
virtual ~BlockFFPILimitedCustom() {}
float update(float inputValue, float inputError, BlockOutputLimiter *outputLimiter = NULL)
{
return calcLimitedOutput(inputValue, inputError, outputLimiter == NULL ? _outputLimiter : *outputLimiter);
@ -176,8 +176,8 @@ public:
SuperBlock(parent, name),
_kP(this, "P"),
_outputLimiter(this, "", isAngularLimit)
{};
virtual ~BlockPLimited() {};
{}
virtual ~BlockPLimited() {}
float update(float input)
{
float difference = 0.0f;
@ -204,8 +204,8 @@ public:
_kD(this, "D"),
_derivative(this, "D"),
_outputLimiter(this, "", isAngularLimit)
{};
virtual ~BlockPDLimited() {};
{}
virtual ~BlockPDLimited() {}
float update(float input)
{
float difference = 0.0f;

View File

@ -39,22 +39,23 @@ px4_add_module(
STACK_MAIN 1200
STACK_MAX 1500
COMPILE_FLAGS
-Wno-extra-semi
-Wno-sign-compare # TODO: fix all sign-compare
SRCS
mavlink.c
mavlink_main.cpp
mavlink_mission.cpp
mavlink_parameters.cpp
mavlink_orb_subscription.cpp
mavlink_messages.cpp
mavlink_stream.cpp
mavlink_rate_limiter.cpp
mavlink_receiver.cpp
mavlink_command_sender.cpp
mavlink_ftp.cpp
mavlink_log_handler.cpp
mavlink_main.cpp
mavlink_messages.cpp
mavlink_mission.cpp
mavlink_orb_subscription.cpp
mavlink_parameters.cpp
mavlink_rate_limiter.cpp
mavlink_receiver.cpp
mavlink_shell.cpp
mavlink_stream.cpp
mavlink_ulog.cpp
mavlink_command_sender.cpp
DEPENDS
platforms__common
)

View File

@ -54,9 +54,9 @@ public:
StreamListItem(MavlinkStream * (*inst)(Mavlink *mavlink), const char *(*name)(), uint16_t (*id)()) :
new_instance(inst),
get_name(name),
get_id(id) {};
get_id(id) {}
~StreamListItem() {};
~StreamListItem() {}
};
extern const StreamListItem *streams_list[];

View File

@ -42,6 +42,7 @@ px4_add_module(
-DMAVLINK_FTP_UNIT_TEST
-DMavlinkStream=MavlinkStreamTest
-DMavlinkFTP=MavlinkFTPTest
-Wno-extra-semi
SRCS
mavlink_tests.cpp
mavlink_ftp_test.cpp

View File

@ -79,7 +79,7 @@ private:
float home_alt, bool home_valid, float default_acceptance_rad);
public:
MissionFeasibilityChecker(Navigator *navigator) : _navigator(navigator) {};
MissionFeasibilityChecker(Navigator *navigator) : _navigator(navigator) {}
~MissionFeasibilityChecker() = default;
MissionFeasibilityChecker(const MissionFeasibilityChecker &) = delete;

View File

@ -165,16 +165,16 @@ protected:
/**
* called when entering the main replay loop
*/
virtual void onEnterMainLoop() {};
virtual void onEnterMainLoop() {}
/**
* called when exiting the main replay loop
*/
virtual void onExitMainLoop() {};
virtual void onExitMainLoop() {}
/**
* called when a new subscription is added
*/
virtual void onSubscriptionAdded(Subscription &sub, uint16_t msg_id) {};
virtual void onSubscriptionAdded(Subscription &sub, uint16_t msg_id) {}
/**
* handle delay until topic can be published.

View File

@ -1645,7 +1645,7 @@ int sdlog2_thread_main(int argc, char *argv[])
log_msg.msg_type = LOG_RPL6_MSG;
log_msg.body.log_RPL6.time_airs_usec = buf.replay.asp_timestamp;
log_msg.body.log_RPL6.indicated_airspeed_m_s = buf.replay.indicated_airspeed_m_s;
log_msg.body.log_RPL6.true_airspeed_m_s = buf.replay.true_airspeed_m_s;;
log_msg.body.log_RPL6.true_airspeed_m_s = buf.replay.true_airspeed_m_s;
LOGBUFFER_WRITE_AND_COUNT(RPL6);
}

View File

@ -67,7 +67,7 @@ Format characters in the format string for binary log messages
#define SDLOG2_FORMAT_H_
#define LOG_PACKET_HEADER_LEN 3
#define LOG_PACKET_HEADER uint8_t head1, head2, msg_type;
#define LOG_PACKET_HEADER uint8_t head1, head2, msg_type
#define LOG_PACKET_HEADER_INIT(id) .head1 = HEAD_BYTE1, .head2 = HEAD_BYTE2, .msg_type = id
// once the logging code is all converted we will remove these from

View File

@ -142,7 +142,7 @@ public:
px4_sem_init(&_lock, 0, _max_readers);
}
~Report() {};
~Report() {}
bool copyData(void *outbuf, int len)
{

View File

@ -254,7 +254,7 @@ void Simulator::update_sensors(mavlink_hil_sensor_t *imu)
RawAirspeedData airspeed = {};
airspeed.temperature = imu->temperature;
airspeed.diff_pressure = imu->diff_pressure + 0.001f * (hrt_absolute_time() & 0x01);;
airspeed.diff_pressure = imu->diff_pressure + 0.001f * (hrt_absolute_time() & 0x01);
write_airspeed_data(&airspeed);
}
@ -491,7 +491,7 @@ void Simulator::handle_message(mavlink_message_t *msg, bool publish)
_hil_ref_timestamp = timestamp;
_hil_ref_lat = lat;
_hil_ref_lon = lon;
_hil_ref_alt = hil_state.alt / 1000.0f;;
_hil_ref_alt = hil_state.alt / 1000.0f;
}
float x;

View File

@ -165,7 +165,7 @@ public:
* @param control_cb Callback invoked when reading controls.
*/
Mixer(ControlCallback control_cb, uintptr_t cb_handle);
virtual ~Mixer() {};
virtual ~Mixer() {}
/**
* Perform the mixing function.
@ -197,7 +197,7 @@ public:
* @param[in] delta_out_max Maximum delta output.
*
*/
virtual void set_max_delta_out_once(float delta_out_max) {};
virtual void set_max_delta_out_once(float delta_out_max) {}
/**
* @brief Set trim offset for this mixer
@ -211,7 +211,7 @@ public:
*
* @param[in] val The value
*/
virtual void set_thrust_factor(float val) {};
virtual void set_thrust_factor(float val) {}
protected:
/** client-supplied callback used when fetching control values */
@ -408,7 +408,7 @@ class __EXPORT NullMixer : public Mixer
{
public:
NullMixer();
~NullMixer() {};
~NullMixer() {}
/**
* Factory method.
@ -428,7 +428,7 @@ public:
virtual unsigned mix(float *outputs, unsigned space, uint16_t *status_reg);
virtual uint16_t get_saturation_status(void);
virtual void groups_required(uint32_t &groups);
virtual void set_offset(float trim) {};
virtual void set_offset(float trim) {}
unsigned set_trim(float trim)
{
return 0;

View File

@ -169,7 +169,7 @@ __EXPORT param_t param_for_index(unsigned index);
/**
* Look up an used parameter by index.
*
* @param param The parameter to obtain the index for.
* @param index The parameter to obtain the index for.
* @return The index of the parameter in use, or -1 if the parameter does not exist.
*/
__EXPORT param_t param_for_used_index(unsigned index);

View File

@ -440,7 +440,7 @@ void Tiltrotor::fill_actuator_outputs()
} else {
_actuators_out_0->control[actuator_controls_s::INDEX_THROTTLE] =
_actuators_mc_in->control[actuator_controls_s::INDEX_THROTTLE];;
_actuators_mc_in->control[actuator_controls_s::INDEX_THROTTLE];
}
_actuators_out_1->timestamp = _actuators_fw_in->timestamp;

View File

@ -116,7 +116,7 @@ public:
/**
* Update external state.
*/
virtual void update_external_state() {};
virtual void update_external_state() {}
/**
* Write control values to actuator output topics.
@ -127,7 +127,7 @@ public:
* Special handling opportunity for the time right after transition to FW
* before TECS is running.
*/
virtual void waiting_on_tecs() {};
virtual void waiting_on_tecs() {}
/**
* Checks for fixed-wing failsafe condition and issues abort request if needed.
@ -142,7 +142,7 @@ public:
void set_idle_mc();
void set_idle_fw();
mode get_mode() {return _vtol_mode;};
mode get_mode() {return _vtol_mode;}
virtual void parameters_update() = 0;