trivial code style cleanup round 2

This commit is contained in:
Daniel Agar 2015-03-27 19:08:44 -04:00
parent 5cc1a5dfda
commit 8aae66b893
56 changed files with 132 additions and 104 deletions

View File

@ -85,7 +85,8 @@ int ar_init_motors(int ardrone_uart, int gpio);
/**
* Set LED pattern.
*/
void ar_set_leds(int ardrone_uart, uint8_t led1_red, uint8_t led1_green, uint8_t led2_red, uint8_t led2_green, uint8_t led3_red, uint8_t led3_green, uint8_t led4_red, uint8_t led4_green);
void ar_set_leds(int ardrone_uart, uint8_t led1_red, uint8_t led1_green, uint8_t led2_red, uint8_t led2_green,
uint8_t led3_red, uint8_t led3_green, uint8_t led4_red, uint8_t led4_green);
/**
* Mix motors and output actuators

View File

@ -127,7 +127,8 @@ __EXPORT extern void hrt_call_at(struct hrt_call *entry, hrt_abstime calltime, h
* Note thet the interval is timed between scheduled, not actual, call times, so the call rate may
* jitter but should not drift.
*/
__EXPORT extern void hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval, hrt_callout callout, void *arg);
__EXPORT extern void hrt_call_every(struct hrt_call *entry, hrt_abstime delay, hrt_abstime interval,
hrt_callout callout, void *arg);
/*
* If this returns true, the entry has been invoked and removed from the callout list,

View File

@ -222,6 +222,7 @@ void frsky_send_frame2(int uart)
float course = 0, lat = 0, lon = 0, speed = 0, alt = 0;
char lat_ns = 0, lon_ew = 0;
int sec = 0;
if (global_pos.timestamp != 0 && hrt_absolute_time() < global_pos.timestamp + 20000) {
time_t time_gps = global_pos.time_utc_usec / 1000000ULL;
struct tm *tm_gps = gmtime(&time_gps);

View File

@ -1,7 +1,8 @@
#include <controllib/block/Block.hpp>
#include <controllib/block/BlockParam.hpp>
class BlockSysIdent : public control::Block {
class BlockSysIdent : public control::Block
{
public:
BlockSysIdent();
private:

View File

@ -44,7 +44,8 @@
#include "Limits.hpp"
namespace math {
namespace math
{
#ifndef CONFIG_ARCH_ARM
#define M_PI_F 3.14159265358979323846f

View File

@ -42,7 +42,8 @@
#include <platforms/px4_defines.h>
#include <stdint.h>
namespace math {
namespace math
{
float __EXPORT min(float val1, float val2);

View File

@ -51,7 +51,7 @@ bool __EXPORT equal(float a, float b, float epsilon)
printf("not equal ->\n\ta: %12.8f\n\tb: %12.8f\n", double(a), double(b));
return false;
} else return true;
} else { return true; }
}
void __EXPORT float2SigExp(
@ -84,10 +84,10 @@ void __EXPORT float2SigExp(
// cheap power since it is integer
if (exp > 0) {
for (int i = 0; i < abs(exp); i++) sig /= 10;
for (int i = 0; i < abs(exp); i++) { sig /= 10; }
} else {
for (int i = 0; i < abs(exp); i++) sig *= 10;
for (int i = 0; i < abs(exp); i++) { sig *= 10; }
}
}

View File

@ -113,6 +113,7 @@ int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channe
case ST24_DECODE_STATE_UNSYNCED:
if (byte == ST24_STX1) {
_decode_state = ST24_DECODE_STATE_GOT_STX1;
} else {
ret = 3;
}

View File

@ -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;

View File

@ -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();

View File

@ -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

View File

@ -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");
}

View File

@ -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);
};

View File

@ -58,7 +58,8 @@ NavigatorMode::~NavigatorMode()
}
void
NavigatorMode::run(bool active) {
NavigatorMode::run(bool active)
{
if (active) {
if (_first_run) {
/* first run */

View File

@ -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);

View File

@ -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;
}
}

View File

@ -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 {
/*

View File

@ -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

View File

@ -66,6 +66,7 @@ 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 */

View File

@ -50,8 +50,7 @@
* @{
*/
struct geofence_result_s
{
struct geofence_result_s {
bool geofence_violated; /**< true if the geofence is violated */
};

View File

@ -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 */

View File

@ -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 */

View File

@ -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;
/**

View File

@ -63,7 +63,8 @@ void UnitTest::_print_assert(const char* msg, const char* test, const char* file
}
/// @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);
}

View File

@ -64,6 +64,7 @@ void PositionEstimator::ModelStatesCallback(const gazebo_msgs::ModelStatesConstP
/* Fill px4 position topic with contents from modelstates topic */
int index = 0;
//XXX: maybe a more clever approach would be to do this not on every loop, need to check if and when
//gazebo rearranges indexes.
for (std::vector<std::string>::const_iterator it = msg->name.begin(); it != msg->name.end(); ++it) {
@ -72,6 +73,7 @@ void PositionEstimator::ModelStatesCallback(const gazebo_msgs::ModelStatesConstP
break;
}
}
msg_v_l_pos.xy_valid = true;
msg_v_l_pos.z_valid = true;
msg_v_l_pos.v_xy_valid = true;

View File

@ -68,11 +68,13 @@ int perf_main(int argc, char *argv[])
if (strcmp(argv[1], "reset") == 0) {
perf_reset_all();
return 0;
} else if (strcmp(argv[1], "latency") == 0) {
perf_print_latency(0 /* stdout */);
fflush(stdout);
return 0;
}
printf("Usage: perf [reset | latency]\n");
return -1;
}

View File

@ -57,6 +57,7 @@ int reboot_main(int argc, char *argv[])
case 'b':
to_bootloader = true;
break;
default:
errx(1, "usage: reboot [-b]\n"
" -b reboot into the bootloader");

View File

@ -71,8 +71,9 @@ int test_adc(int argc, char *argv[])
/* read all channels available */
ssize_t count = read(fd, data, sizeof(data));
if (count < 0)
if (count < 0) {
goto errout_with_dev;
}
unsigned channels = count / sizeof(data[0]);
@ -88,7 +89,7 @@ int test_adc(int argc, char *argv[])
errout_with_dev:
if (fd != 0) close(fd);
if (fd != 0) { close(fd); }
return OK;
}

View File

@ -190,7 +190,8 @@ int test_hott_telemetry(int argc, char *argv[])
warnx("PASS: Received %d out of %d valid byte pairs from the HoTT receiver device.", received_count, max_polls);
} else {
warnx("WARN: Received %d out of %d byte pairs of which %d were valid from the HoTT receiver device.", received_count, max_polls, valid_count);
warnx("WARN: Received %d out of %d byte pairs of which %d were valid from the HoTT receiver device.", received_count,
max_polls, valid_count);
}
} else {

View File

@ -146,9 +146,10 @@ int test_uart_baudchange(int argc, char *argv[])
/* uart2 -> */
r = write(uart2, sample_uart2, sizeof(sample_uart2));
if (r > 0)
if (r > 0) {
uart2_nwrite += r;
}
}
close(uart2);

View File

@ -8,7 +8,8 @@
#include "gtest/gtest.h"
TEST(SUMDTest, SUMD) {
TEST(SUMDTest, SUMD)
{
const char *filepath = "testdata/sumd_data.txt";
warnx("loading data from: %s", filepath);