mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 13:55:18 +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:
parent
ac4835ef67
commit
1f293795e7
26 changed files with 99 additions and 109 deletions
23
src/board.h
23
src/board.h
|
@ -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];
|
||||
|
@ -151,24 +150,22 @@ typedef struct sensor_data_t
|
|||
int updated;
|
||||
} sensor_data_t;
|
||||
|
||||
typedef void (* sensorInitFuncPtr)(sensor_align_e align); // sensor init prototype
|
||||
typedef void (* sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
|
||||
typedef void (* baroOpFuncPtr)(void); // baro start operation
|
||||
typedef void (* baroCalculateFuncPtr)(int32_t *pressure, int32_t *temperature); // baro calculation (filled params are pressure and temperature)
|
||||
typedef void (* serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app
|
||||
typedef uint16_t (* rcReadRawDataPtr)(uint8_t chan); // used by receiver driver to return channel data
|
||||
typedef void (* pidControllerFuncPtr)(void); // pid controller function prototype
|
||||
typedef void (*sensorInitFuncPtr)(sensor_align_e align); // sensor init prototype
|
||||
typedef void (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype
|
||||
typedef void (*baroOpFuncPtr)(void); // baro start operation
|
||||
typedef void (*baroCalculateFuncPtr)(int32_t *pressure, int32_t *temperature); // baro calculation (filled params are pressure and temperature)
|
||||
typedef void (*serialReceiveCallbackPtr)(uint16_t data); // used by serial drivers to return frames to app
|
||||
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;
|
||||
|
|
|
@ -78,7 +78,7 @@ void beep_code(char first, char second, char third, char pause)
|
|||
patternChar[1] = second;
|
||||
patternChar[2] = third;
|
||||
patternChar[3] = pause;
|
||||
switch(patternChar[icnt]) {
|
||||
switch (patternChar[icnt]) {
|
||||
case 'M':
|
||||
Duration = 100;
|
||||
break;
|
||||
|
@ -121,7 +121,7 @@ static void beep(uint16_t pulse)
|
|||
buzzerIsOn = 0;
|
||||
BEEP_OFF;
|
||||
buzzerLastToggleTime = millis();
|
||||
if (toggleBeep >0)
|
||||
if (toggleBeep > 0)
|
||||
toggleBeep--;
|
||||
beepDone = 1;
|
||||
}
|
||||
|
|
|
@ -297,7 +297,7 @@ static float _atof(const char *p)
|
|||
float sign, value, scale;
|
||||
|
||||
// Skip leading white space, if any.
|
||||
while (white_space(*p) ) {
|
||||
while (white_space(*p)) {
|
||||
p += 1;
|
||||
}
|
||||
|
||||
|
@ -381,7 +381,7 @@ static char *ftoa(float x, char *floatString)
|
|||
else
|
||||
x -= 0.0005f;
|
||||
|
||||
value = (int32_t) (x * 1000.0f); // Convert float * 1000 to an integer
|
||||
value = (int32_t)(x * 1000.0f); // Convert float * 1000 to an integer
|
||||
|
||||
itoa(abs(value), intString1, 10); // Create string from abs of integer value
|
||||
|
||||
|
|
|
@ -72,7 +72,7 @@ void activateConfig(void)
|
|||
{
|
||||
uint8_t i;
|
||||
for (i = 0; i < PITCH_LOOKUP_LENGTH; i++)
|
||||
lookupPitchRollRC[i] = (2500 + cfg.rcExpo8 * (i * i - 25)) * i * (int32_t) cfg.rcRate8 / 2500;
|
||||
lookupPitchRollRC[i] = (2500 + cfg.rcExpo8 * (i * i - 25)) * i * (int32_t)cfg.rcRate8 / 2500;
|
||||
|
||||
for (i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) {
|
||||
int16_t tmp = 10 * i - cfg.thrMid8;
|
||||
|
@ -81,8 +81,8 @@ void activateConfig(void)
|
|||
y = 100 - cfg.thrMid8;
|
||||
if (tmp < 0)
|
||||
y = cfg.thrMid8;
|
||||
lookupThrottleRC[i] = 10 * cfg.thrMid8 + tmp * (100 - cfg.thrExpo8 + (int32_t) cfg.thrExpo8 * (tmp * tmp) / (y * y)) / 10;
|
||||
lookupThrottleRC[i] = mcfg.minthrottle + (int32_t) (mcfg.maxthrottle - mcfg.minthrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE]
|
||||
lookupThrottleRC[i] = 10 * cfg.thrMid8 + tmp * (100 - cfg.thrExpo8 + (int32_t)cfg.thrExpo8 * (tmp * tmp) / (y * y)) / 10;
|
||||
lookupThrottleRC[i] = mcfg.minthrottle + (int32_t)(mcfg.maxthrottle - mcfg.minthrottle) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE]
|
||||
}
|
||||
|
||||
setPIDController(cfg.pidController);
|
||||
|
@ -128,7 +128,7 @@ retry:
|
|||
|
||||
if (FLASH_ErasePage(FLASH_WRITE_ADDR) == FLASH_COMPLETE) {
|
||||
for (i = 0; i < sizeof(master_t); i += 4) {
|
||||
status = FLASH_ProgramWord(FLASH_WRITE_ADDR + i, *(uint32_t *) ((char *)&mcfg + i));
|
||||
status = FLASH_ProgramWord(FLASH_WRITE_ADDR + i, *(uint32_t *)((char *)&mcfg + i));
|
||||
if (status != FLASH_COMPLETE) {
|
||||
FLASH_Lock();
|
||||
tries++;
|
||||
|
|
|
@ -189,9 +189,9 @@ static int32_t bmp085_get_pressure(uint32_t up)
|
|||
|
||||
// *****calculate B4************
|
||||
x1 = (bmp085.cal_param.ac3 * b6) >> 13;
|
||||
x2 = (bmp085.cal_param.b1 * ((b6 * b6) >> 12) ) >> 16;
|
||||
x2 = (bmp085.cal_param.b1 * ((b6 * b6) >> 12)) >> 16;
|
||||
x3 = ((x1 + x2) + 2) >> 2;
|
||||
b4 = (bmp085.cal_param.ac4 * (uint32_t) (x3 + 32768)) >> 15;
|
||||
b4 = (bmp085.cal_param.ac4 * (uint32_t)(x3 + 32768)) >> 15;
|
||||
|
||||
b7 = ((uint32_t)(up - b3) * (50000 >> bmp085.oversampling_setting));
|
||||
if (b7 < 0x80000000) {
|
||||
|
@ -249,7 +249,7 @@ static void bmp085_get_up(void)
|
|||
convOverrun++;
|
||||
|
||||
i2cRead(BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data);
|
||||
bmp085_up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2]) >> (8 - bmp085.oversampling_setting);
|
||||
bmp085_up = (((uint32_t)data[0] << 16) | ((uint32_t)data[1] << 8) | (uint32_t)data[2]) >> (8 - bmp085.oversampling_setting);
|
||||
}
|
||||
|
||||
static void bmp085_calculate(int32_t *pressure, int32_t *temperature)
|
||||
|
|
|
@ -71,7 +71,7 @@ void gpioPinRemapConfig(uint32_t remap, bool enable)
|
|||
}
|
||||
|
||||
if (enable)
|
||||
tmpreg |= (tmp << ((remap >> 0x15)*0x10));
|
||||
tmpreg |= (tmp << ((remap >> 0x15) * 0x10));
|
||||
|
||||
if ((remap & 0x80000000) == 0x80000000)
|
||||
AFIO->MAPR2 = tmpreg;
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -61,7 +61,7 @@ void hcsr04_init(sonar_config_t config)
|
|||
// enable AFIO for EXTI support - already done is drv_system.c
|
||||
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph, ENABLE);
|
||||
|
||||
switch(config) {
|
||||
switch (config) {
|
||||
case sonar_pwm56:
|
||||
trigger_pin = Pin_8; // PWM5 (PB8) - 5v tolerant
|
||||
echo_pin = Pin_9; // PWM6 (PB9) - 5v tolerant
|
||||
|
|
|
@ -174,7 +174,7 @@ static void ms5611_calculate(int32_t *pressure, int32_t *temperature)
|
|||
sens -= (11 * delt) >> 1;
|
||||
}
|
||||
}
|
||||
press = ((((int64_t)ms5611_up * sens ) >> 21) - off) >> 15;
|
||||
press = ((((int64_t)ms5611_up * sens) >> 21) - off) >> 15;
|
||||
|
||||
if (pressure)
|
||||
*pressure = press;
|
||||
|
|
|
@ -51,7 +51,7 @@ enum {
|
|||
TYPE_S = 0x80
|
||||
};
|
||||
|
||||
typedef void (* pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors
|
||||
typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors
|
||||
|
||||
static pwmPortData_t pwmPorts[MAX_PORTS];
|
||||
static uint16_t captures[MAX_INPUTS];
|
||||
|
|
|
@ -253,7 +253,7 @@ void applyChangedBits(softSerial_t *softSerial)
|
|||
{
|
||||
if (softSerial->rxEdge == TRAILING) {
|
||||
uint8_t bitToSet;
|
||||
for (bitToSet = softSerial->rxLastLeadingEdgeAtBitIndex; bitToSet < softSerial->rxBitIndex ; bitToSet++) {
|
||||
for (bitToSet = softSerial->rxLastLeadingEdgeAtBitIndex; bitToSet < softSerial->rxBitIndex; bitToSet++) {
|
||||
softSerial->internalRxBuffer |= 1 << bitToSet;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -10,7 +10,7 @@ void SetSysClock(bool overclock);
|
|||
void systemBeep(bool onoff);
|
||||
static void beepRev4(bool onoff);
|
||||
static void beepRev5(bool onoff);
|
||||
void (* systemBeepPtr)(bool onoff) = NULL;
|
||||
void (*systemBeepPtr)(bool onoff) = NULL;
|
||||
#endif
|
||||
|
||||
static void cycleCounterInit(void)
|
||||
|
|
22
src/gps.c
22
src/gps.c
|
@ -436,7 +436,7 @@ static void gpsNewData(uint16_t c)
|
|||
#endif
|
||||
// dTnav calculation
|
||||
// Time for calculating x,y speed and navigation pids
|
||||
dTnav = (float) (millis() - nav_loopTimer) / 1000.0f;
|
||||
dTnav = (float)(millis() - nav_loopTimer) / 1000.0f;
|
||||
nav_loopTimer = millis();
|
||||
// prevent runup from bad GPS
|
||||
dTnav = min(dTnav, 1.0f);
|
||||
|
@ -612,7 +612,7 @@ static bool check_missed_wp(void)
|
|||
static void GPS_distance_cm_bearing(int32_t * lat1, int32_t * lon1, int32_t * lat2, int32_t * lon2, uint32_t * dist, int32_t * bearing)
|
||||
{
|
||||
float dLat = *lat2 - *lat1; // difference of latitude in 1/10 000 000 degrees
|
||||
float dLon = (float) (*lon2 - *lon1) * GPS_scaleLonDown;
|
||||
float dLon = (float)(*lon2 - *lon1) * GPS_scaleLonDown;
|
||||
*dist = sqrtf(sq(dLat) + sq(dLon)) * 1.113195f;
|
||||
|
||||
*bearing = 9000.0f + atan2f(-dLat, dLon) * 5729.57795f; // Convert the output radians to 100xdeg
|
||||
|
@ -644,8 +644,8 @@ static void GPS_calc_velocity(void)
|
|||
|
||||
if (init) {
|
||||
float tmp = 1.0f / dTnav;
|
||||
actual_speed[GPS_X] = (float) (GPS_coord[LON] - last[LON]) * GPS_scaleLonDown * tmp;
|
||||
actual_speed[GPS_Y] = (float) (GPS_coord[LAT] - last[LAT]) * tmp;
|
||||
actual_speed[GPS_X] = (float)(GPS_coord[LON] - last[LON]) * GPS_scaleLonDown * tmp;
|
||||
actual_speed[GPS_Y] = (float)(GPS_coord[LAT] - last[LAT]) * tmp;
|
||||
|
||||
actual_speed[GPS_X] = (actual_speed[GPS_X] + speed_old[GPS_X]) / 2;
|
||||
actual_speed[GPS_Y] = (actual_speed[GPS_Y] + speed_old[GPS_Y]) / 2;
|
||||
|
@ -670,7 +670,7 @@ static void GPS_calc_velocity(void)
|
|||
//
|
||||
static void GPS_calc_location_error(int32_t *target_lat, int32_t *target_lng, int32_t *gps_lat, int32_t *gps_lng)
|
||||
{
|
||||
error[LON] = (float) (*target_lng - *gps_lng) * GPS_scaleLonDown; // X Error
|
||||
error[LON] = (float)(*target_lng - *gps_lng) * GPS_scaleLonDown; // X Error
|
||||
error[LAT] = *target_lat - *gps_lat; // Y Error
|
||||
}
|
||||
|
||||
|
@ -698,7 +698,7 @@ static void GPS_calc_poshold(void)
|
|||
d = 0;
|
||||
#endif
|
||||
|
||||
nav[axis] +=d;
|
||||
nav[axis] += d;
|
||||
nav[axis] = constrain(nav[axis], -NAV_BANK_MAX, NAV_BANK_MAX);
|
||||
navPID[axis].integrator = poshold_ratePID[axis].integrator;
|
||||
}
|
||||
|
@ -774,7 +774,7 @@ static int16_t GPS_calc_desired_speed(int16_t max_speed, bool _slow)
|
|||
// limit the ramp up of the speed
|
||||
// waypoint_speed_gov is reset to 0 at each new WP command
|
||||
if (max_speed > waypoint_speed_gov) {
|
||||
waypoint_speed_gov += (int) (100.0f * dTnav); // increase at .5/ms
|
||||
waypoint_speed_gov += (int)(100.0f * dTnav); // increase at .5/ms
|
||||
max_speed = waypoint_speed_gov;
|
||||
}
|
||||
return max_speed;
|
||||
|
@ -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
|
||||
|
@ -1180,7 +1178,7 @@ static bool gpsNewFrameUBLOX(uint8_t data)
|
|||
case 5:
|
||||
_step++;
|
||||
_ck_b += (_ck_a += data); // checksum byte
|
||||
_payload_length += (uint16_t) (data << 8);
|
||||
_payload_length += (uint16_t)(data << 8);
|
||||
if (_payload_length > 512) {
|
||||
_payload_length = 0;
|
||||
_step = 0;
|
||||
|
|
|
@ -430,7 +430,7 @@ void mixTable(void)
|
|||
break;
|
||||
|
||||
case MULTITYPE_DUALCOPTER:
|
||||
for (i = 4; i < 6; i++ ) {
|
||||
for (i = 4; i < 6; i++) {
|
||||
servo[i] = axisPID[5 - i] * servoDirection(i, 1); // mix and setup direction
|
||||
servo[i] += servoMiddle(i);
|
||||
}
|
||||
|
|
2
src/mw.c
2
src/mw.c
|
@ -365,7 +365,7 @@ static void pidRewrite(void)
|
|||
AngleRateTmp = (((int32_t)(cfg.yawRate + 27) * rcCommand[2]) >> 5);
|
||||
} else {
|
||||
if (!f.ANGLE_MODE) { //control is GYRO based (ACRO and HORIZON - direct sticks control is applied to rate PID
|
||||
AngleRateTmp = ((int32_t) (cfg.rollPitchRate + 27) * rcCommand[axis]) >> 4;
|
||||
AngleRateTmp = ((int32_t)(cfg.rollPitchRate + 27) * rcCommand[axis]) >> 4;
|
||||
if (f.HORIZON_MODE) {
|
||||
// mix up angle error to desired AngleRateTmp to add a little auto-level feel
|
||||
AngleRateTmp += (errorAngle * cfg.I8[PIDLEVEL]) >> 8;
|
||||
|
|
|
@ -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;
|
||||
|
|
|
@ -158,14 +158,14 @@ uint8_t read8(void)
|
|||
uint16_t read16(void)
|
||||
{
|
||||
uint16_t t = read8();
|
||||
t += (uint16_t) read8() << 8;
|
||||
t += (uint16_t)read8() << 8;
|
||||
return t;
|
||||
}
|
||||
|
||||
uint32_t read32(void)
|
||||
{
|
||||
uint32_t t = read16();
|
||||
t += (uint32_t) read16() << 16;
|
||||
t += (uint32_t)read16() << 16;
|
||||
return t;
|
||||
}
|
||||
|
||||
|
|
|
@ -88,13 +88,13 @@ void hottV4FormatAndSendGPSResponse(void)
|
|||
void hottV4GPSUpdate(void)
|
||||
{
|
||||
// Number of Satelites
|
||||
HoTTV4GPSModule.GPSNumSat=GPS_numSat;
|
||||
HoTTV4GPSModule.GPSNumSat = GPS_numSat;
|
||||
if (f.GPS_FIX > 0) {
|
||||
// GPS fix
|
||||
HoTTV4GPSModule.GPS_fix = 0x66; // Displays a 'f' for fix
|
||||
|
||||
// latitude
|
||||
HoTTV4GPSModule.LatitudeNS=(GPS_coord[LAT]<0);
|
||||
HoTTV4GPSModule.LatitudeNS = (GPS_coord[LAT] < 0);
|
||||
uint8_t deg = GPS_coord[LAT] / 100000;
|
||||
uint32_t sec = (GPS_coord[LAT] - (deg * 100000)) * 6;
|
||||
uint8_t min = sec / 10000;
|
||||
|
@ -106,7 +106,7 @@ void hottV4GPSUpdate(void)
|
|||
HoTTV4GPSModule.LatitudeSecHigh = sec >> 8;
|
||||
|
||||
// longitude
|
||||
HoTTV4GPSModule.longitudeEW=(GPS_coord[LON]<0);
|
||||
HoTTV4GPSModule.longitudeEW = (GPS_coord[LON] < 0);
|
||||
deg = GPS_coord[LON] / 100000;
|
||||
sec = (GPS_coord[LON] - (deg * 100000)) * 6;
|
||||
min = sec / 10000;
|
||||
|
@ -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();
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue