1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 21:35:44 +03:00

format code properly

match the comment from pullrequest about spacing
remains : some hand alignment for comment and wrong /** */ usage.
This commit is contained in:
treymarc 2014-05-08 00:36:19 +00:00
parent ac4835ef67
commit 1f293795e7
26 changed files with 99 additions and 109 deletions

View file

@ -142,8 +142,7 @@ enum {
TEMP_UPDATED = 1 << 3
};
typedef struct sensor_data_t
{
typedef struct sensor_data_t {
int16_t gyro[3];
int16_t acc[3];
int16_t mag[3];
@ -159,16 +158,14 @@ typedef void (* serialReceiveCallbackPtr)(uint16_t data); // used by serial dr
typedef uint16_t (*rcReadRawDataPtr)(uint8_t chan); // used by receiver driver to return channel data
typedef void (*pidControllerFuncPtr)(void); // pid controller function prototype
typedef struct sensor_t
{
typedef struct sensor_t {
sensorInitFuncPtr init; // initialize function
sensorReadFuncPtr read; // read 3 axis data function
sensorReadFuncPtr temperature; // read temperature if available
float scale; // scalefactor (currently used for gyro only, todo for accel)
} sensor_t;
typedef struct baro_t
{
typedef struct baro_t {
uint16_t ut_delay;
uint16_t up_delay;
baroOpFuncPtr start_ut;

View file

@ -1,7 +1,6 @@
#pragma once
typedef enum
{
typedef enum {
Mode_AIN = 0x0,
Mode_IN_FLOATING = 0x04,
Mode_IPD = 0x28,
@ -12,15 +11,13 @@ typedef enum
Mode_AF_PP = 0x18
} GPIO_Mode;
typedef enum
{
typedef enum {
Speed_10MHz = 1,
Speed_2MHz,
Speed_50MHz
} GPIO_Speed;
typedef enum
{
typedef enum {
Pin_0 = 0x0001,
Pin_1 = 0x0002,
Pin_2 = 0x0004,
@ -40,8 +37,7 @@ typedef enum
Pin_All = 0xFFFF
} GPIO_Pin;
typedef struct
{
typedef struct {
uint16_t pin;
GPIO_Mode mode;
GPIO_Speed speed;

View file

@ -1056,8 +1056,7 @@ typedef struct {
uint32_t heading_accuracy;
} ubx_nav_velned;
typedef struct
{
typedef struct {
uint8_t chn; // Channel number, 255 for SVx not assigned to channel
uint8_t svid; // Satellite ID
uint8_t flags; // Bitmask
@ -1068,8 +1067,7 @@ typedef struct
int32_t prRes; // Pseudo range residual in centimetres
} ubx_nav_svinfo_channel;
typedef struct
{
typedef struct {
uint32_t time; // GPS Millisecond time of week
uint8_t numCh; // Number of channels
uint8_t globalFlags; // Bitmask, Chip hardware generation 0:Antaris, 1:u-blox 5, 2:u-blox 6

View file

@ -28,8 +28,7 @@ void sbusInit(rcReadRawDataPtr *callback)
core.numRCChannels = SBUS_MAX_CHANNEL;
}
struct sbus_dat
{
struct sbus_dat {
unsigned int chan0 : 11;
unsigned int chan1 : 11;
unsigned int chan2 : 11;
@ -44,8 +43,7 @@ struct sbus_dat
unsigned int chan11 : 11;
} __attribute__ ((__packed__));
typedef union
{
typedef union {
uint8_t in[SBUS_FRAME_SIZE];
struct sbus_dat msg;
} sbus_msg;

View file

@ -265,7 +265,8 @@ void handleHoTTTelemetry(void)
switch (c) {
case 0x8A:
if (sensors(SENSOR_GPS)) hottV4FormatAndSendGPSResponse();
if (sensors(SENSOR_GPS))
hottV4FormatAndSendGPSResponse();
break;
case 0x8E:
hottV4FormatAndSendEAMResponse();