aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorDaniel Agar <daniel@agar.ca>2015-03-27 19:08:44 -0400
committerDaniel Agar <daniel@agar.ca>2015-03-27 23:38:58 -0400
commit8aae66b893444c74a22ad7beb89e3828e0444108 (patch)
tree893833e818d8138360f8fa0bf5554dc6b036f369 /src/modules
parent5cc1a5dfdae53626c3cdf35e3d7b60f1a4ca68ed (diff)
downloadpx4-firmware-8aae66b893444c74a22ad7beb89e3828e0444108.tar.gz
px4-firmware-8aae66b893444c74a22ad7beb89e3828e0444108.tar.bz2
px4-firmware-8aae66b893444c74a22ad7beb89e3828e0444108.zip
trivial code style cleanup round 2
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/commander/calibration_routines.cpp3
-rw-r--r--src/modules/commander/gyro_calibration.cpp4
-rw-r--r--src/modules/controllib/block/BlockParam.hpp4
-rw-r--r--src/modules/controllib/blocks.hpp5
-rw-r--r--src/modules/fw_att_control/fw_att_control_params.c3
-rw-r--r--src/modules/fw_pos_control_l1/mtecs/mTecs.h6
-rw-r--r--src/modules/gpio_led/gpio_led.c2
-rw-r--r--src/modules/land_detector/LandDetector.cpp4
-rw-r--r--src/modules/land_detector/MulticopterLandDetector.h4
-rw-r--r--src/modules/mavlink/mavlink_receiver.h4
-rw-r--r--src/modules/mavlink/mavlink_stream.h6
-rw-r--r--src/modules/mc_att_control_multiplatform/mc_att_control.h6
-rw-r--r--src/modules/navigator/mission_block.h6
-rw-r--r--src/modules/navigator/mission_feasibility_checker.h3
-rw-r--r--src/modules/navigator/navigator_mode.cpp3
-rw-r--r--src/modules/navigator/navigator_mode.h4
-rw-r--r--src/modules/px4iofirmware/px4io.h3
-rw-r--r--src/modules/systemlib/cpuload.c3
-rw-r--r--src/modules/systemlib/hx_stream.h4
-rw-r--r--src/modules/systemlib/mcu_version.h4
-rw-r--r--src/modules/systemlib/mixer/mixer_group.cpp4
-rw-r--r--src/modules/systemlib/pwm_limit/pwm_limit.h3
-rw-r--r--src/modules/systemlib/systemlib.c5
-rw-r--r--src/modules/uORB/topics/geofence_result.h3
-rw-r--r--src/modules/uORB/topics/home_position.h3
-rw-r--r--src/modules/uORB/topics/mission_result.h3
-rw-r--r--src/modules/uORB/topics/tecs_status.h6
-rw-r--r--src/modules/uORB/uORB.h5
-rw-r--r--src/modules/uavcan/sensors/baro.hpp6
-rw-r--r--src/modules/uavcan/sensors/gnss.hpp6
-rw-r--r--src/modules/uavcan/sensors/mag.hpp6
-rw-r--r--src/modules/uavcan/uavcan_main.hpp6
-rw-r--r--src/modules/unit_test/unit_test.cpp5
33 files changed, 77 insertions, 65 deletions
diff --git a/src/modules/commander/calibration_routines.cpp b/src/modules/commander/calibration_routines.cpp
index 5796204bf..290e83a0b 100644
--- a/src/modules/commander/calibration_routines.cpp
+++ b/src/modules/commander/calibration_routines.cpp
@@ -45,7 +45,8 @@
int sphere_fit_least_squares(const float x[], const float y[], const float z[],
- unsigned int size, unsigned int max_iterations, float delta, float *sphere_x, float *sphere_y, float *sphere_z, float *sphere_radius)
+ unsigned int size, unsigned int max_iterations, float delta, float *sphere_x, float *sphere_y, float *sphere_z,
+ float *sphere_radius)
{
float x_sumplain = 0.0f;
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index 8a70cf66e..d4a6d6801 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -245,7 +245,7 @@ int do_gyro_calibration(int mavlink_fd)
mavlink_log_critical(mavlink_fd, CAL_FAILED_APPLY_CAL_MSG);
}
}
-
+
if (failed) {
mavlink_and_console_log_critical(mavlink_fd, "ERROR: failed to set offset params");
res = ERROR;
@@ -376,7 +376,7 @@ int do_gyro_calibration(int mavlink_fd)
}
}
- #endif
+#endif
if (res == OK) {
/* auto-save to EEPROM */
diff --git a/src/modules/controllib/block/BlockParam.hpp b/src/modules/controllib/block/BlockParam.hpp
index a64d0139e..437e43bfb 100644
--- a/src/modules/controllib/block/BlockParam.hpp
+++ b/src/modules/controllib/block/BlockParam.hpp
@@ -58,7 +58,7 @@ public:
*
* @param parent_prefix Set to true to include the parent name in the parameter name
*/
- BlockParamBase(Block *parent, const char *name, bool parent_prefix=true);
+ BlockParamBase(Block *parent, const char *name, bool parent_prefix = true);
virtual ~BlockParamBase() {};
virtual void update() = 0;
const char *getName() { return param_name(_handle); }
@@ -75,7 +75,7 @@ class BlockParam : public BlockParamBase
{
public:
BlockParam(Block *block, const char *name,
- bool parent_prefix=true);
+ bool parent_prefix = true);
T get();
void set(T val);
void update();
diff --git a/src/modules/controllib/blocks.hpp b/src/modules/controllib/blocks.hpp
index bffc355a8..65600190b 100644
--- a/src/modules/controllib/blocks.hpp
+++ b/src/modules/controllib/blocks.hpp
@@ -114,7 +114,7 @@ public:
// methods
BlockLowPass(SuperBlock *parent, const char *name) :
Block(parent, name),
- _state(0.0f/0.0f /* initialize to invalid val, force into is_finite() check on first call */),
+ _state(0.0f / 0.0f /* initialize to invalid val, force into is_finite() check on first call */),
_fCut(this, "") // only one parameter, no need to name
{};
virtual ~BlockLowPass() {};
@@ -492,8 +492,9 @@ public:
X = V1 * float(sqrt(-2 * float(log(S)) / S));
- } else
+ } else {
X = V2 * float(sqrt(-2 * float(log(S)) / S));
+ }
phase = 1 - phase;
return X * getStdDev() + getMean();
diff --git a/src/modules/fw_att_control/fw_att_control_params.c b/src/modules/fw_att_control/fw_att_control_params.c
index 6ab3ddbfc..cfc5ae965 100644
--- a/src/modules/fw_att_control/fw_att_control_params.c
+++ b/src/modules/fw_att_control/fw_att_control_params.c
@@ -136,7 +136,8 @@ PARAM_DEFINE_FLOAT(FW_PR_IMAX, 0.2f);
* @max 2.0
* @group FW Attitude Control
*/
-PARAM_DEFINE_FLOAT(FW_P_ROLLFF, 0.0f); //xxx: set to 0 as default, see comment in ECL_PitchController::control_attitude (float turn_offset = ...)
+PARAM_DEFINE_FLOAT(FW_P_ROLLFF,
+ 0.0f); //xxx: set to 0 as default, see comment in ECL_PitchController::control_attitude (float turn_offset = ...)
/**
* Roll rate proportional Gain
diff --git a/src/modules/fw_pos_control_l1/mtecs/mTecs.h b/src/modules/fw_pos_control_l1/mtecs/mTecs.h
index ae6867d38..4c2db0c64 100644
--- a/src/modules/fw_pos_control_l1/mtecs/mTecs.h
+++ b/src/modules/fw_pos_control_l1/mtecs/mTecs.h
@@ -65,19 +65,19 @@ public:
* Control in altitude setpoint and speed mode
*/
int updateAltitudeSpeed(float flightPathAngle, float altitude, float altitudeSp, float airspeed,
- float airspeedSp, tecs_mode mode, LimitOverride limitOverride);
+ float airspeedSp, tecs_mode mode, LimitOverride limitOverride);
/*
* Control in flightPathAngle setpoint (flollow a slope etc.) and speed mode
*/
int updateFlightPathAngleSpeed(float flightPathAngle, float flightPathAngleSp, float airspeed,
- float airspeedSp, tecs_mode mode, LimitOverride limitOverride);
+ float airspeedSp, tecs_mode mode, LimitOverride limitOverride);
/*
* Control in flightPathAngle setpoint (flollow a slope etc.) and acceleration mode (base case)
*/
int updateFlightPathAngleAcceleration(float flightPathAngle, float flightPathAngleSp, float airspeedFiltered,
- float accelerationLongitudinalSp, tecs_mode mode, LimitOverride limitOverride);
+ float accelerationLongitudinalSp, tecs_mode mode, LimitOverride limitOverride);
/*
* Reset all integrators
diff --git a/src/modules/gpio_led/gpio_led.c b/src/modules/gpio_led/gpio_led.c
index b759b429e..2ff3fc276 100644
--- a/src/modules/gpio_led/gpio_led.c
+++ b/src/modules/gpio_led/gpio_led.c
@@ -184,11 +184,13 @@ int gpio_led_main(int argc, char *argv[])
warnx("start, using pin: %s", pin_name);
exit(0);
}
+
} else if (!strcmp(argv[1], "stop")) {
if (gpio_led_started) {
gpio_led_started = false;
warnx("stop");
exit(0);
+
} else {
errx(1, "not running");
}
diff --git a/src/modules/land_detector/LandDetector.cpp b/src/modules/land_detector/LandDetector.cpp
index a4fbb9861..7c830fc07 100644
--- a/src/modules/land_detector/LandDetector.cpp
+++ b/src/modules/land_detector/LandDetector.cpp
@@ -46,8 +46,8 @@
LandDetector::LandDetector() :
_landDetectedPub(-1),
_landDetected({0, false}),
- _taskShouldExit(false),
- _taskIsRunning(false)
+ _taskShouldExit(false),
+ _taskIsRunning(false)
{
// ctor
}
diff --git a/src/modules/land_detector/MulticopterLandDetector.h b/src/modules/land_detector/MulticopterLandDetector.h
index 70df91f43..8c57416b5 100644
--- a/src/modules/land_detector/MulticopterLandDetector.h
+++ b/src/modules/land_detector/MulticopterLandDetector.h
@@ -102,13 +102,13 @@ private:
int _actuatorsSub;
int _armingSub;
int _parameterSub;
- int _attitudeSub;
+ int _attitudeSub;
struct vehicle_global_position_s _vehicleGlobalPosition; /**< the result from global position subscription */
struct vehicle_status_s _vehicleStatus;
struct actuator_controls_s _actuators;
struct actuator_armed_s _arming;
- struct vehicle_attitude_s _vehicleAttitude;
+ struct vehicle_attitude_s _vehicleAttitude;
uint64_t _landTimer; /**< timestamp in microseconds since a possible land was detected*/
};
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index b510dbbb7..1d214b948 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -188,6 +188,6 @@ private:
uint64_t _time_offset;
/* do not allow copying this class */
- MavlinkReceiver(const MavlinkReceiver&);
- MavlinkReceiver operator=(const MavlinkReceiver&);
+ MavlinkReceiver(const MavlinkReceiver &);
+ MavlinkReceiver operator=(const MavlinkReceiver &);
};
diff --git a/src/modules/mavlink/mavlink_stream.h b/src/modules/mavlink/mavlink_stream.h
index ef22dc443..5e39bbbdf 100644
--- a/src/modules/mavlink/mavlink_stream.h
+++ b/src/modules/mavlink/mavlink_stream.h
@@ -89,7 +89,7 @@ public:
virtual unsigned get_size() = 0;
protected:
- Mavlink * _mavlink;
+ Mavlink *_mavlink;
unsigned int _interval;
virtual void send(const hrt_abstime t) = 0;
@@ -98,8 +98,8 @@ private:
hrt_abstime _last_sent;
/* do not allow top copying this class */
- MavlinkStream(const MavlinkStream&);
- MavlinkStream& operator=(const MavlinkStream&);
+ MavlinkStream(const MavlinkStream &);
+ MavlinkStream &operator=(const MavlinkStream &);
};
diff --git a/src/modules/mc_att_control_multiplatform/mc_att_control.h b/src/modules/mc_att_control_multiplatform/mc_att_control.h
index 52ba369c1..1242c7fe3 100644
--- a/src/modules/mc_att_control_multiplatform/mc_att_control.h
+++ b/src/modules/mc_att_control_multiplatform/mc_att_control.h
@@ -88,9 +88,9 @@ private:
bool _task_should_exit; /**< if true, sensor task should exit */
bool _actuators_0_circuit_breaker_enabled; /**< circuit breaker to suppress output */
- px4::Publisher<px4_vehicle_attitude_setpoint> * _att_sp_pub; /**< attitude setpoint publication */
- px4::Publisher<px4_vehicle_rates_setpoint> * _v_rates_sp_pub; /**< rate setpoint publication */
- px4::Publisher<px4_actuator_controls_0> * _actuators_0_pub; /**< attitude actuator controls publication */
+ px4::Publisher<px4_vehicle_attitude_setpoint> *_att_sp_pub; /**< attitude setpoint publication */
+ px4::Publisher<px4_vehicle_rates_setpoint> *_v_rates_sp_pub; /**< rate setpoint publication */
+ px4::Publisher<px4_actuator_controls_0> *_actuators_0_pub; /**< attitude actuator controls publication */
px4::NodeHandle _n;
diff --git a/src/modules/navigator/mission_block.h b/src/modules/navigator/mission_block.h
index adf50bc39..ec3e30582 100644
--- a/src/modules/navigator/mission_block.h
+++ b/src/modules/navigator/mission_block.h
@@ -83,9 +83,9 @@ protected:
*/
void mission_item_to_position_setpoint(const mission_item_s *item, position_setpoint_s *sp);
- /**
- * Set previous position setpoint to current setpoint
- */
+ /**
+ * Set previous position setpoint to current setpoint
+ */
void set_previous_pos_setpoint();
/**
diff --git a/src/modules/navigator/mission_feasibility_checker.h b/src/modules/navigator/mission_feasibility_checker.h
index 96c9209d3..9a77a6dc2 100644
--- a/src/modules/navigator/mission_feasibility_checker.h
+++ b/src/modules/navigator/mission_feasibility_checker.h
@@ -78,7 +78,8 @@ public:
/*
* Returns true if mission is feasible and false otherwise
*/
- bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence, float home_alt);
+ bool checkMissionFeasible(bool isRotarywing, dm_item_t dm_current, size_t nMissionItems, Geofence &geofence,
+ float home_alt);
};
diff --git a/src/modules/navigator/navigator_mode.cpp b/src/modules/navigator/navigator_mode.cpp
index 2f322031c..f7ccda0cb 100644
--- a/src/modules/navigator/navigator_mode.cpp
+++ b/src/modules/navigator/navigator_mode.cpp
@@ -58,7 +58,8 @@ NavigatorMode::~NavigatorMode()
}
void
-NavigatorMode::run(bool active) {
+NavigatorMode::run(bool active)
+{
if (active) {
if (_first_run) {
/* first run */
diff --git a/src/modules/navigator/navigator_mode.h b/src/modules/navigator/navigator_mode.h
index de5545dcb..0839d9be6 100644
--- a/src/modules/navigator/navigator_mode.h
+++ b/src/modules/navigator/navigator_mode.h
@@ -92,8 +92,8 @@ private:
/* this class has ptr data members, so it should not be copied,
* consequently the copy constructors are private.
*/
- NavigatorMode(const NavigatorMode&);
- NavigatorMode operator=(const NavigatorMode&);
+ NavigatorMode(const NavigatorMode &);
+ NavigatorMode operator=(const NavigatorMode &);
};
#endif
diff --git a/src/modules/px4iofirmware/px4io.h b/src/modules/px4iofirmware/px4io.h
index 93a33490f..8192c5b50 100644
--- a/src/modules/px4iofirmware/px4io.h
+++ b/src/modules/px4iofirmware/px4io.h
@@ -219,7 +219,8 @@ extern int dsm_init(const char *device);
extern bool dsm_input(uint16_t *values, uint16_t *num_values, uint8_t *n_bytes, uint8_t **bytes);
extern void dsm_bind(uint16_t cmd, int pulses);
extern int sbus_init(const char *device);
-extern bool sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop, uint16_t max_channels);
+extern bool sbus_input(uint16_t *values, uint16_t *num_values, bool *sbus_failsafe, bool *sbus_frame_drop,
+ uint16_t max_channels);
extern void sbus1_output(uint16_t *values, uint16_t num_values);
extern void sbus2_output(uint16_t *values, uint16_t num_values);
diff --git a/src/modules/systemlib/cpuload.c b/src/modules/systemlib/cpuload.c
index 7aa2f3a5f..b41896abd 100644
--- a/src/modules/systemlib/cpuload.c
+++ b/src/modules/systemlib/cpuload.c
@@ -97,7 +97,8 @@ void cpuload_initialize_once()
system_load.tasks[system_load.total_count].start_time = now;
system_load.tasks[system_load.total_count].total_runtime = 0;
system_load.tasks[system_load.total_count].curr_start_time = 0;
- system_load.tasks[system_load.total_count].tcb = sched_gettcb(system_load.total_count); // it is assumed that these static threads have consecutive PIDs
+ system_load.tasks[system_load.total_count].tcb = sched_gettcb(
+ system_load.total_count); // it is assumed that these static threads have consecutive PIDs
system_load.tasks[system_load.total_count].valid = true;
}
}
diff --git a/src/modules/systemlib/hx_stream.h b/src/modules/systemlib/hx_stream.h
index 1f3927222..b674f192d 100644
--- a/src/modules/systemlib/hx_stream.h
+++ b/src/modules/systemlib/hx_stream.h
@@ -103,7 +103,7 @@ __EXPORT extern void hx_stream_reset(hx_stream_t stream);
/**
* Prepare to send a frame.
*
- * Use this in conjunction with hx_stream_send_next to
+ * Use this in conjunction with hx_stream_send_next to
* set the frame to be transmitted.
*
* Use hx_stream_send() to write to the stream fd directly.
@@ -124,7 +124,7 @@ __EXPORT extern int hx_stream_start(hx_stream_t stream,
* calling hx_stream_start first.
*
* @param stream A handle returned from hx_stream_init.
- * @return The byte to send, or -1 if there is
+ * @return The byte to send, or -1 if there is
* nothing left to send.
*/
__EXPORT extern int hx_stream_send_next(hx_stream_t stream);
diff --git a/src/modules/systemlib/mcu_version.h b/src/modules/systemlib/mcu_version.h
index e951e1e39..f40ac069e 100644
--- a/src/modules/systemlib/mcu_version.h
+++ b/src/modules/systemlib/mcu_version.h
@@ -50,7 +50,7 @@ enum MCU_REV {
/**
* Reports the microcontroller unique id.
*
- * This ID is guaranteed to be unique for every mcu.
+ * This ID is guaranteed to be unique for every mcu.
* @param uid_96_bit A uint32_t[3] array to copy the data to.
*/
__EXPORT void mcu_unique_id(uint32_t *uid_96_bit);
@@ -62,6 +62,6 @@ __EXPORT void mcu_unique_id(uint32_t *uid_96_bit);
* @param revstr The full chip name string
* @return The silicon revision / version number as integer
*/
-__EXPORT int mcu_version(char* rev, char** revstr);
+__EXPORT int mcu_version(char *rev, char **revstr);
__END_DECLS
diff --git a/src/modules/systemlib/mixer/mixer_group.cpp b/src/modules/systemlib/mixer/mixer_group.cpp
index 3ed99fba0..4220b168d 100644
--- a/src/modules/systemlib/mixer/mixer_group.cpp
+++ b/src/modules/systemlib/mixer/mixer_group.cpp
@@ -76,8 +76,9 @@ MixerGroup::add_mixer(Mixer *mixer)
mpp = &_first;
- while (*mpp != nullptr)
+ while (*mpp != nullptr) {
mpp = &((*mpp)->_next);
+ }
*mpp = mixer;
mixer->_next = nullptr;
@@ -185,6 +186,7 @@ MixerGroup::load_from_buf(const char *buf, unsigned &buflen)
/* only adjust buflen if parsing was successful */
buflen = resid;
debug("SUCCESS - buflen: %d", buflen);
+
} else {
/*
diff --git a/src/modules/systemlib/pwm_limit/pwm_limit.h b/src/modules/systemlib/pwm_limit/pwm_limit.h
index 6a667ac6f..6ec9f4b7e 100644
--- a/src/modules/systemlib/pwm_limit/pwm_limit.h
+++ b/src/modules/systemlib/pwm_limit/pwm_limit.h
@@ -72,7 +72,8 @@ typedef struct {
__EXPORT void pwm_limit_init(pwm_limit_t *limit);
-__EXPORT void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm, const uint16_t *min_pwm, const uint16_t *max_pwm, const float *output, uint16_t *effective_pwm, pwm_limit_t *limit);
+__EXPORT void pwm_limit_calc(const bool armed, const unsigned num_channels, const uint16_t *disarmed_pwm,
+ const uint16_t *min_pwm, const uint16_t *max_pwm, const float *output, uint16_t *effective_pwm, pwm_limit_t *limit);
__END_DECLS
diff --git a/src/modules/systemlib/systemlib.c b/src/modules/systemlib/systemlib.c
index 82183b0d7..280c30023 100644
--- a/src/modules/systemlib/systemlib.c
+++ b/src/modules/systemlib/systemlib.c
@@ -66,10 +66,11 @@ systemreset(bool to_bootloader)
/* XXX wow, this is evil - write a magic number into backup register zero */
*(uint32_t *)0x40002850 = 0xb007b007;
}
+
up_systemreset();
/* lock up here */
- while(true);
+ while (true);
}
static void kill_task(FAR struct tcb_s *tcb, FAR void *arg);
@@ -87,7 +88,7 @@ static void kill_task(FAR struct tcb_s *tcb, FAR void *arg)
kill(tcb->pid, SIGUSR1);
}
-int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, char * const argv[])
+int task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, char *const argv[])
{
int pid;
diff --git a/src/modules/uORB/topics/geofence_result.h b/src/modules/uORB/topics/geofence_result.h
index b07e04499..8d32dfc0a 100644
--- a/src/modules/uORB/topics/geofence_result.h
+++ b/src/modules/uORB/topics/geofence_result.h
@@ -50,8 +50,7 @@
* @{
*/
-struct geofence_result_s
-{
+struct geofence_result_s {
bool geofence_violated; /**< true if the geofence is violated */
};
diff --git a/src/modules/uORB/topics/home_position.h b/src/modules/uORB/topics/home_position.h
index d747b5f43..02e17cdd7 100644
--- a/src/modules/uORB/topics/home_position.h
+++ b/src/modules/uORB/topics/home_position.h
@@ -55,8 +55,7 @@
/**
* GPS home position in WGS84 coordinates.
*/
-struct home_position_s
-{
+struct home_position_s {
uint64_t timestamp; /**< Timestamp (microseconds since system boot) */
double lat; /**< Latitude in degrees */
diff --git a/src/modules/uORB/topics/mission_result.h b/src/modules/uORB/topics/mission_result.h
index 2ddc529a3..16e7f2f12 100644
--- a/src/modules/uORB/topics/mission_result.h
+++ b/src/modules/uORB/topics/mission_result.h
@@ -53,8 +53,7 @@
* @{
*/
-struct mission_result_s
-{
+struct mission_result_s {
unsigned seq_reached; /**< Sequence of the mission item which has been reached */
unsigned seq_current; /**< Sequence of the current mission item */
bool reached; /**< true if mission has been reached */
diff --git a/src/modules/uORB/topics/tecs_status.h b/src/modules/uORB/topics/tecs_status.h
index ddca19d61..3c858901c 100644
--- a/src/modules/uORB/topics/tecs_status.h
+++ b/src/modules/uORB/topics/tecs_status.h
@@ -60,9 +60,9 @@ typedef enum {
TECS_MODE_CLIMBOUT
} tecs_mode;
- /**
- * Internal values of the (m)TECS fixed wing speed alnd altitude control system
- */
+/**
+* Internal values of the (m)TECS fixed wing speed alnd altitude control system
+*/
struct tecs_status_s {
uint64_t timestamp; /**< timestamp, in microseconds since system start */
diff --git a/src/modules/uORB/uORB.h b/src/modules/uORB/uORB.h
index b54f0322b..44dc6614f 100644
--- a/src/modules/uORB/uORB.h
+++ b/src/modules/uORB/uORB.h
@@ -166,7 +166,7 @@ extern orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *d
* node in /obj if required and publishes the initial data.
*
* Any number of advertisers may publish to a topic; publications are atomic
- * but co-ordination between publishers is not provided by the ORB.
+ * but co-ordination between publishers is not provided by the ORB.
*
* @param meta The uORB metadata (usually from the ORB_ID() macro)
* for the topic.
@@ -184,7 +184,8 @@ extern orb_advert_t orb_advertise(const struct orb_metadata *meta, const void *d
* ORB_DEFINE with no corresponding ORB_DECLARE)
* this function will return -1 and set errno to ENOENT.
*/
-extern orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, int priority) __EXPORT;
+extern orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance,
+ int priority) __EXPORT;
/**
diff --git a/src/modules/uavcan/sensors/baro.hpp b/src/modules/uavcan/sensors/baro.hpp
index c7bbc5af8..16cd476ea 100644
--- a/src/modules/uavcan/sensors/baro.hpp
+++ b/src/modules/uavcan/sensors/baro.hpp
@@ -47,7 +47,7 @@ class UavcanBarometerBridge : public UavcanCDevSensorBridgeBase
public:
static const char *const NAME;
- UavcanBarometerBridge(uavcan::INode& node);
+ UavcanBarometerBridge(uavcan::INode &node);
const char *get_name() const override { return NAME; }
@@ -58,9 +58,9 @@ private:
void air_data_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::air_data::StaticAirData> &msg);
- typedef uavcan::MethodBinder<UavcanBarometerBridge*,
+ typedef uavcan::MethodBinder < UavcanBarometerBridge *,
void (UavcanBarometerBridge::*)
- (const uavcan::ReceivedDataStructure<uavcan::equipment::air_data::StaticAirData>&)>
+ (const uavcan::ReceivedDataStructure<uavcan::equipment::air_data::StaticAirData> &) >
AirDataCbBinder;
uavcan::Subscriber<uavcan::equipment::air_data::StaticAirData, AirDataCbBinder> _sub_air_data;
diff --git a/src/modules/uavcan/sensors/gnss.hpp b/src/modules/uavcan/sensors/gnss.hpp
index 96ff9404f..4b94d9306 100644
--- a/src/modules/uavcan/sensors/gnss.hpp
+++ b/src/modules/uavcan/sensors/gnss.hpp
@@ -56,7 +56,7 @@ class UavcanGnssBridge : public IUavcanSensorBridge
public:
static const char *const NAME;
- UavcanGnssBridge(uavcan::INode& node);
+ UavcanGnssBridge(uavcan::INode &node);
const char *get_name() const override { return NAME; }
@@ -72,8 +72,8 @@ private:
*/
void gnss_fix_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix> &msg);
- typedef uavcan::MethodBinder<UavcanGnssBridge*,
- void (UavcanGnssBridge::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix>&)>
+ typedef uavcan::MethodBinder < UavcanGnssBridge *,
+ void (UavcanGnssBridge::*)(const uavcan::ReceivedDataStructure<uavcan::equipment::gnss::Fix> &) >
FixCbBinder;
uavcan::INode &_node;
diff --git a/src/modules/uavcan/sensors/mag.hpp b/src/modules/uavcan/sensors/mag.hpp
index db38aee1d..b74afeb0b 100644
--- a/src/modules/uavcan/sensors/mag.hpp
+++ b/src/modules/uavcan/sensors/mag.hpp
@@ -47,7 +47,7 @@ class UavcanMagnetometerBridge : public UavcanCDevSensorBridgeBase
public:
static const char *const NAME;
- UavcanMagnetometerBridge(uavcan::INode& node);
+ UavcanMagnetometerBridge(uavcan::INode &node);
const char *get_name() const override { return NAME; }
@@ -59,9 +59,9 @@ private:
void mag_sub_cb(const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Magnetometer> &msg);
- typedef uavcan::MethodBinder<UavcanMagnetometerBridge*,
+ typedef uavcan::MethodBinder < UavcanMagnetometerBridge *,
void (UavcanMagnetometerBridge::*)
- (const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Magnetometer>&)>
+ (const uavcan::ReceivedDataStructure<uavcan::equipment::ahrs::Magnetometer> &) >
MagCbBinder;
uavcan::Subscriber<uavcan::equipment::ahrs::Magnetometer, MagCbBinder> _sub_mag;
diff --git a/src/modules/uavcan/uavcan_main.hpp b/src/modules/uavcan/uavcan_main.hpp
index 19b9b4b48..96b3ec1a6 100644
--- a/src/modules/uavcan/uavcan_main.hpp
+++ b/src/modules/uavcan/uavcan_main.hpp
@@ -82,7 +82,7 @@ public:
static int start(uavcan::NodeID node_id, uint32_t bitrate);
- Node& get_node() { return _node; }
+ Node &get_node() { return _node; }
// TODO: move the actuator mixing stuff into the ESC controller class
static int control_callback(uintptr_t handle, uint8_t control_group, uint8_t control_index, float &input);
@@ -94,7 +94,7 @@ public:
void print_info();
- static UavcanNode* instance() { return _instance; }
+ static UavcanNode *instance() { return _instance; }
private:
void fill_node_info();
@@ -122,7 +122,7 @@ private:
UavcanEscController _esc_controller;
- List<IUavcanSensorBridge*> _sensor_bridges; ///< List of active sensor bridges
+ List<IUavcanSensorBridge *> _sensor_bridges; ///< List of active sensor bridges
MixerGroup *_mixers = nullptr;
diff --git a/src/modules/unit_test/unit_test.cpp b/src/modules/unit_test/unit_test.cpp
index b7568ce3a..c45d7888a 100644
--- a/src/modules/unit_test/unit_test.cpp
+++ b/src/modules/unit_test/unit_test.cpp
@@ -57,13 +57,14 @@ void UnitTest::print_results(void)
}
/// @brief Used internally to the ut_assert macro to print assert failures.
-void UnitTest::_print_assert(const char* msg, const char* test, const char* file, int line)
+void UnitTest::_print_assert(const char *msg, const char *test, const char *file, int line)
{
warnx("Assertion failed: %s - %s (%s:%d)", msg, test, file, line);
}
/// @brief Used internally to the ut_compare macro to print assert failures.
-void UnitTest::_print_compare(const char* msg, const char *v1_text, int v1, const char *v2_text, int v2, const char* file, int line)
+void UnitTest::_print_compare(const char *msg, const char *v1_text, int v1, const char *v2_text, int v2,
+ const char *file, int line)
{
warnx("Compare failed: %s - (%s:%d) (%s:%d) (%s:%d)", msg, v1_text, v1, v2_text, v2, file, line);
}