fix code style if trivial one line difference

This commit is contained in:
Daniel Agar 2015-03-02 14:36:04 -05:00 committed by Lorenz Meier
parent c147424fe7
commit c2abb0f82a
37 changed files with 38 additions and 33 deletions

View File

@ -54,7 +54,7 @@ __BEGIN_DECLS
#include <arch/board/board.h>
#define UDID_START 0x1FFF7A10
/****************************************************************************************************
* Definitions
****************************************************************************************************/

View File

@ -52,7 +52,7 @@ __BEGIN_DECLS
/* these headers are not C++ safe */
#include <stm32.h>
#include <arch/board/board.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/

View File

@ -54,7 +54,7 @@ __BEGIN_DECLS
#include <arch/board/board.h>
#define UDID_START 0x1FFF7A10
/****************************************************************************************************
* Definitions
****************************************************************************************************/

View File

@ -87,7 +87,7 @@ __EXPORT void stm32_boardinitialize(void)
stm32_configgpio(GPIO_RELAY1_EN);
stm32_configgpio(GPIO_RELAY2_EN);
/* turn off - all leds are active low */
/* turn off - all leds are active low */
stm32_gpiowrite(GPIO_LED1, true);
stm32_gpiowrite(GPIO_LED2, true);
stm32_gpiowrite(GPIO_LED3, true);

View File

@ -126,7 +126,7 @@ __EXPORT void stm32_boardinitialize(void)
stm32_configgpio(GPIO_SBUS_INPUT); /* xxx alternate function */
stm32_configgpio(GPIO_SBUS_OUTPUT);
/* sbus output enable is active low - disable it by default */
stm32_gpiowrite(GPIO_SBUS_OENABLE, true);
stm32_configgpio(GPIO_SBUS_OENABLE);

View File

@ -35,7 +35,7 @@
* @file drv_airspeed.h
*
* Airspeed driver interface.
*
*
* @author Simon Wilks
*/

View File

@ -60,7 +60,7 @@
/** play the numbered script in (arg), repeating forever */
#define BLINKM_PLAY_SCRIPT _BLINKMIOC(2)
/**
/**
* Set the user script; (arg) is a pointer to an array of script lines,
* where each line is an array of four bytes giving <duration>, <command>, arg[0-2]
*

View File

@ -36,7 +36,7 @@
/**
* @file drv_orb_dev.h
*
*
* uORB published object driver.
*/

View File

@ -117,7 +117,7 @@ enum oreoled_macro {
OREOLED_PARAM_MACRO_ENUM_COUNT
};
/*
/*
structure passed to OREOLED_SET_RGB ioctl()
Note that the driver scales the brightness to 0 to 255, regardless
of the hardware scaling

View File

@ -46,6 +46,6 @@ __BEGIN_DECLS
/*
* Initialise the timer
*/
__EXPORT extern int pwm_input_main(int argc, char * argv[]);
__EXPORT extern int pwm_input_main(int argc, char *argv[]);
__END_DECLS

View File

@ -50,4 +50,4 @@
/* interface factories */
extern device::Device *HMC5883_SPI_interface(int bus) weak_function;
extern device::Device *HMC5883_I2C_interface(int bus) weak_function;
typedef device::Device* (*HMC5883_constructor)(int);
typedef device::Device *(*HMC5883_constructor)(int);

View File

@ -82,4 +82,4 @@ extern bool crc4(uint16_t *n_prom);
/* interface factories */
extern device::Device *MS5611_spi_interface(ms5611::prom_u &prom_buf, uint8_t busnum) weak_function;
extern device::Device *MS5611_i2c_interface(ms5611::prom_u &prom_buf, uint8_t busnum) weak_function;
typedef device::Device* (*MS5611_constructor)(ms5611::prom_u &prom_buf, uint8_t busnum);
typedef device::Device *(*MS5611_constructor)(ms5611::prom_u &prom_buf, uint8_t busnum);

View File

@ -34,7 +34,7 @@
/*
* @file params.c
*
*
* Parameters for fixedwing demo
*/

View File

@ -34,7 +34,7 @@
/*
* @file params.h
*
*
* Definition of parameters for fixedwing example
*/

View File

@ -35,7 +35,7 @@
/*
* @file flow_position_estimator_params.c
*
*
* Parameters for position estimator
*/

View File

@ -35,7 +35,7 @@
/*
* @file flow_position_estimator_params.h
*
*
* Parameters for position estimator
*/

View File

@ -118,7 +118,7 @@ const rot_lookup_t rot_lookup[] = {
* Get the rotation matrix
*/
__EXPORT void
get_rot_matrix(enum Rotation rot, math::Matrix<3,3> *rot_matrix);
get_rot_matrix(enum Rotation rot, math::Matrix<3, 3> *rot_matrix);
/**

View File

@ -76,7 +76,7 @@ private:
method is checked for further adavancing in the state machine (e.g. when
to power up the motors) */
LaunchMethod* launchMethods[1];
LaunchMethod *launchMethods[1];
control::BlockParamInt launchdetection_on;
control::BlockParamFloat throttlePreTakeoff;

View File

@ -158,6 +158,6 @@ uint8_t st24_common_crc8(uint8_t *ptr, uint8_t len);
* @return 0 for success (a decoded packet), 1 for no packet yet (accumulating), 2 for unknown packet, 3 for out of sync, 4 for checksum error
*/
__EXPORT int st24_decode(uint8_t byte, uint8_t *rssi, uint8_t *rx_count, uint16_t *channel_count,
uint16_t *channels, uint16_t max_chan_count);
uint16_t *channels, uint16_t max_chan_count);
__END_DECLS

View File

@ -177,6 +177,7 @@ int parameters_update(const struct attitude_estimator_ekf_param_handles *h, stru
for (int i = 0; i < 3; i++) {
param_get(h->moment_inertia_J[i], &(p->moment_inertia_J[3 * i + i]));
}
param_get(h->use_moment_inertia, &(p->use_moment_inertia));
return OK;

View File

@ -57,4 +57,5 @@
* @return 0 on success, 1 on failure
*/
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);

View File

@ -57,7 +57,7 @@ PARAM_DEFINE_FLOAT(FWB_V_CMD, 12.0f); // commanded velocity
PARAM_DEFINE_FLOAT(FWB_V_MAX, 16.0f); // maximum commanded velocity
// rate of climb
// this is what rate of climb is commanded (in m/s)
// this is what rate of climb is commanded (in m/s)
// when the pitch stick is fully defelcted in simple mode
PARAM_DEFINE_FLOAT(FWB_CR_MAX, 1.0f);

View File

@ -80,6 +80,7 @@ MavlinkStream::update(const hrt_abstime t)
if (dt > 0 && dt >= interval) {
/* interval expired, send message */
send(t);
if (const_rate()) {
_last_sent = (t / _interval) * _interval;

View File

@ -76,7 +76,7 @@ public:
* @return true: system is inside fence, false: system is outside fence
*/
bool inside(const struct vehicle_global_position_s &global_position,
const struct vehicle_gps_position_s &gps_position,float baro_altitude_amsl);
const struct vehicle_gps_position_s &gps_position, float baro_altitude_amsl);
bool inside_polygon(double lat, double lon, float altitude);
int clearDm();

View File

@ -15,6 +15,7 @@ void inertial_filter_predict(float dt, float x[2], float acc)
if (!isfinite(acc)) {
acc = 0.0f;
}
x[0] += x[1] * dt + acc * dt * dt / 2.0f;
x[1] += acc * dt;
}

View File

@ -142,7 +142,7 @@ sbus1_output(uint16_t *values, uint16_t num_values)
value = (uint16_t)(((values[i] - SBUS_SCALE_OFFSET) / SBUS_SCALE_FACTOR) + .5f);
/*protect from out of bounds values and limit to 11 bits*/
if (value > 0x07ff ) {
if (value > 0x07ff) {
value = 0x07ff;
}

View File

@ -682,7 +682,7 @@ PARAM_DEFINE_INT32(SENS_FLOW_ROT, 0);
*
* @group Sensor Calibration
*/
PARAM_DEFINE_FLOAT(SENS_BOARD_Y_OFF, 0.0f);
PARAM_DEFINE_FLOAT(SENS_BOARD_Y_OFF, 0.0f);
/**
* Board rotation X (Roll) offset

View File

@ -45,7 +45,7 @@
#include <px4.h>
#include <systemlib/circuit_breaker.h>
bool circuit_breaker_enabled(const char* breaker, int32_t magic)
bool circuit_breaker_enabled(const char *breaker, int32_t magic)
{
int32_t val;
(void)PX4_PARAM_GET_BYNAME(breaker, &val);

View File

@ -61,7 +61,7 @@
__BEGIN_DECLS
extern "C" __EXPORT bool circuit_breaker_enabled(const char* breaker, int32_t magic);
extern "C" __EXPORT bool circuit_breaker_enabled(const char *breaker, int32_t magic);
__END_DECLS

View File

@ -39,7 +39,7 @@
#pragma once
__BEGIN_DECLS
__BEGIN_DECLS
/**
* Check the RC calibration

View File

@ -92,7 +92,7 @@ struct esc_status_s {
struct {
enum ESC_VENDOR esc_vendor; /**< Vendor of current ESC */
uint32_t esc_errorcount; /**< Number of reported errors by ESC - if supported */
int32_t esc_rpm; /**< Motor RPM, negative for reverse rotation [RPM] - if supported */
int32_t esc_rpm; /**< Motor RPM, negative for reverse rotation [RPM] - if supported */
float esc_voltage; /**< Voltage measured from current ESC [V] - if supported */
float esc_current; /**< Current measured from current ESC [A] - if supported */
float esc_temperature; /**< Temperature measured from current ESC [degC] - if supported */

View File

@ -65,7 +65,7 @@ struct fence_vertex_s {
* This is the position of a geofence
*
*/
struct fence_s {
struct fence_s {
unsigned count; /**< number of actual vertices */
struct fence_vertex_s vertices[GEOFENCE_MAX_VERTICES];
};

View File

@ -66,6 +66,7 @@ int DemoOffboardPositionSetpoints::main()
pose.pose.position.z = 1;
_local_position_sp_pub.publish(pose);
}
return 0;
}

View File

@ -162,7 +162,7 @@ int test_jig_voltages(int argc, char *argv[])
errout_with_dev:
if (fd != 0) close(fd);
if (fd != 0) { close(fd); }
return ret;
}

View File

@ -126,7 +126,7 @@ int test_rc(int argc, char *argv[])
warnx("TIMEOUT, less than 10 Hz updates");
(void)close(_rc_sub);
return ERROR;
}
}
} else {
/* key pressed, bye bye */

View File

@ -95,7 +95,7 @@ int test_uart_send(int argc, char *argv[])
/* input handling */
char *uart_name = "/dev/ttyS3";
if (argc > 1) uart_name = argv[1];
if (argc > 1) { uart_name = argv[1]; }
/* assuming NuttShell is on UART1 (/dev/ttyS0) */
int test_uart = open(uart_name, O_RDWR | O_NONBLOCK | O_NOCTTY); //

View File

@ -52,5 +52,5 @@ __EXPORT int usb_connected_main(int argc, char *argv[]);
int
usb_connected_main(int argc, char *argv[])
{
return stm32_gpioread(GPIO_OTGFS_VBUS) ? 0:1;
return stm32_gpioread(GPIO_OTGFS_VBUS) ? 0 : 1;
}