1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 09:45:33 +03:00

Converted tabs to spaces prior to IO merge from betaflight

This commit is contained in:
Martin Budden 2016-07-31 23:40:49 +01:00
parent add744d4c8
commit a0ba45f8b3
20 changed files with 103 additions and 103 deletions

View file

@ -87,7 +87,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
putf(putp, ch); written++;
} else {
char lz = 0;
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
char lng = 0;
#endif
int w = 0;
@ -99,7 +99,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
if (ch >= '0' && ch <= '9') {
ch = a2i(ch, &fmt, 10, &w);
}
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
if (ch == 'l') {
ch = *(fmt++);
lng = 1;
@ -109,7 +109,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
case 0:
goto abort;
case 'u':{
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
if (lng)
uli2a(va_arg(va, unsigned long int), 10, 0, bf);
else
@ -119,7 +119,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
break;
}
case 'd':{
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
if (lng)
li2a(va_arg(va, unsigned long int), bf);
else
@ -130,7 +130,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va)
}
case 'x':
case 'X':
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
#ifdef REQUIRE_PRINTF_LONG_SUPPORT
if (lng)
uli2a(va_arg(va, unsigned long int), 16, (ch == 'X'), bf);
else

View file

@ -66,10 +66,10 @@ To use the printf you need to supply your own character output function,
something like :
void putc ( void* p, char c)
{
while (!SERIAL_PORT_EMPTY) ;
SERIAL_PORT_TX_REGISTER = c;
}
{
while (!SERIAL_PORT_EMPTY) ;
SERIAL_PORT_TX_REGISTER = c;
}
Before you can call printf you need to initialize it to use your
character output function with something like:

View file

@ -991,7 +991,7 @@ static void validateAndFixConfig(void)
#if defined(COLIBRI_RACE)
masterConfig.serialConfig.portConfigs[0].functionMask = FUNCTION_MSP;
if(featureConfigured(FEATURE_RX_SERIAL)) {
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
}
#endif

View file

@ -62,7 +62,7 @@
#define BLOCK_DATA_UPDATE_CONTINUOUS ((uint8_t)0x00)
#define BLE_MSB ((uint8_t)0x40)
#define BLE_MSB ((uint8_t)0x40)
#define BOOT ((uint8_t)0x80)

View file

@ -49,12 +49,12 @@ extern uint8_t mpuLowPassFilter;
static bool mpuSpi6000InitDone = false;
// Bits
#define BIT_SLEEP 0x40
#define BIT_H_RESET 0x80
#define BITS_CLKSEL 0x07
#define MPU_CLK_SEL_PLLGYROX 0x01
#define MPU_CLK_SEL_PLLGYROZ 0x03
#define MPU_EXT_SYNC_GYROX 0x02
#define BIT_SLEEP 0x40
#define BIT_H_RESET 0x80
#define BITS_CLKSEL 0x07
#define MPU_CLK_SEL_PLLGYROX 0x01
#define MPU_CLK_SEL_PLLGYROZ 0x03
#define MPU_EXT_SYNC_GYROX 0x02
#define BITS_FS_250DPS 0x00
#define BITS_FS_500DPS 0x08
#define BITS_FS_1000DPS 0x10
@ -74,9 +74,9 @@ static bool mpuSpi6000InitDone = false;
#define BITS_DLPF_CFG_2100HZ_NOLPF 0x07
#define BITS_DLPF_CFG_MASK 0x07
#define BIT_INT_ANYRD_2CLEAR 0x10
#define BIT_RAW_RDY_EN 0x01
#define BIT_RAW_RDY_EN 0x01
#define BIT_I2C_IF_DIS 0x10
#define BIT_INT_STATUS_DATA 0x01
#define BIT_INT_STATUS_DATA 0x01
#define BIT_GYRO 3
#define BIT_ACC 2
#define BIT_TEMP 1

View file

@ -207,8 +207,8 @@ void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resource, uint8_t ind
{
ioRec_t *ioRec = IO_Rec(io);
ioRec->owner = owner;
ioRec->resource = resource;
ioRec->index = index;
ioRec->resource = resource;
ioRec->index = index;
}
void IORelease(IO_t io)

View file

@ -49,8 +49,8 @@ void ledInit(void)
#endif
#ifdef LED2
{
.gpio = LED2_GPIO,
.cfg = { LED2_PIN, Mode_Out_PP, Speed_2MHz }
.gpio = LED2_GPIO,
.cfg = { LED2_PIN, Mode_Out_PP, Speed_2MHz }
}
#endif
};

View file

@ -227,7 +227,7 @@ void mixerUseConfigs(
flight3DConfig_t *flight3DConfigToUse,
struct escAndServoConfig_s *escAndServoConfigToUse,
mixerConfig_t *mixerConfigToUse,
struct rxConfig_s *rxConfigToUse);
struct rxConfig_s *rxConfigToUse);
void writeAllMotors(int16_t mc);
void mixerLoadMix(int index, motorMixer_t *customMixers);

View file

@ -48,15 +48,15 @@
#if defined(NAV_AUTO_MAG_DECLINATION)
/* Declination calculation code from PX4 project */
/* set this always to the sampling in degrees for the table below */
#define SAMPLING_RES 10.0f
#define SAMPLING_MIN_LAT -60.0f
#define SAMPLING_MAX_LAT 60.0f
#define SAMPLING_MIN_LON -180.0f
#define SAMPLING_MAX_LON 180.0f
#define SAMPLING_RES 10.0f
#define SAMPLING_MIN_LAT -60.0f
#define SAMPLING_MAX_LAT 60.0f
#define SAMPLING_MIN_LON -180.0f
#define SAMPLING_MAX_LON 180.0f
static const int8_t declination_table[13][37] = \
{
{ 46, 45, 44, 42, 41, 40, 38, 36, 33, 28, 23, 16, 10, 4, -1, -5, -9, -14, -19, -26, -33, -40, -48, -55, -61, -66, -71, -74, -75, -72, -61, -25, 22, 40, 45, 47, 46 },
{ 46, 45, 44, 42, 41, 40, 38, 36, 33, 28, 23, 16, 10, 4, -1, -5, -9, -14, -19, -26, -33, -40, -48, -55, -61, -66, -71, -74, -75, -72, -61, -25, 22, 40, 45, 47, 46 },
{ 30, 30, 30, 30, 29, 29, 29, 29, 27, 24, 18, 11, 3, -3, -9, -12, -15, -17, -21, -26, -32, -39, -45, -51, -55, -57, -56, -53, -44, -31, -14, 0, 13, 21, 26, 29, 30 },
{ 21, 22, 22, 22, 22, 22, 22, 22, 21, 18, 13, 5, -3, -11, -17, -20, -21, -22, -23, -25, -29, -35, -40, -44, -45, -44, -40, -32, -22, -12, -3, 3, 9, 14, 18, 20, 21 },
{ 16, 17, 17, 17, 17, 17, 16, 16, 16, 13, 8, 0, -9, -16, -21, -24, -25, -25, -23, -20, -21, -24, -28, -31, -31, -29, -24, -17, -9, -3, 0, 4, 7, 10, 13, 15, 16 },
@ -73,64 +73,64 @@ static const int8_t declination_table[13][37] = \
static float get_lookup_table_val(unsigned lat_index, unsigned lon_index)
{
return declination_table[lat_index][lon_index];
return declination_table[lat_index][lon_index];
}
float geoCalculateMagDeclination(gpsLocation_t * llh) // degrees units
{
/*
* If the values exceed valid ranges, return zero as default
* as we have no way of knowing what the closest real value
* would be.
*/
/*
* If the values exceed valid ranges, return zero as default
* as we have no way of knowing what the closest real value
* would be.
*/
float lat = llh->lat / 10000000.0f;
float lon = llh->lon / 10000000.0f;
if (lat < -90.0f || lat > 90.0f ||
lon < -180.0f || lon > 180.0f) {
return 0.0f;
}
if (lat < -90.0f || lat > 90.0f ||
lon < -180.0f || lon > 180.0f) {
return 0.0f;
}
/* round down to nearest sampling resolution */
int min_lat = (int)(lat / SAMPLING_RES) * SAMPLING_RES;
int min_lon = (int)(lon / SAMPLING_RES) * SAMPLING_RES;
/* round down to nearest sampling resolution */
int min_lat = (int)(lat / SAMPLING_RES) * SAMPLING_RES;
int min_lon = (int)(lon / SAMPLING_RES) * SAMPLING_RES;
/* for the rare case of hitting the bounds exactly
* the rounding logic wouldn't fit, so enforce it.
*/
/* for the rare case of hitting the bounds exactly
* the rounding logic wouldn't fit, so enforce it.
*/
/* limit to table bounds - required for maxima even when table spans full globe range */
if (lat <= SAMPLING_MIN_LAT) {
min_lat = SAMPLING_MIN_LAT;
}
/* limit to table bounds - required for maxima even when table spans full globe range */
if (lat <= SAMPLING_MIN_LAT) {
min_lat = SAMPLING_MIN_LAT;
}
if (lat >= SAMPLING_MAX_LAT) {
min_lat = (int)(lat / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES;
}
if (lat >= SAMPLING_MAX_LAT) {
min_lat = (int)(lat / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES;
}
if (lon <= SAMPLING_MIN_LON) {
min_lon = SAMPLING_MIN_LON;
}
if (lon <= SAMPLING_MIN_LON) {
min_lon = SAMPLING_MIN_LON;
}
if (lon >= SAMPLING_MAX_LON) {
min_lon = (int)(lon / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES;
}
if (lon >= SAMPLING_MAX_LON) {
min_lon = (int)(lon / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES;
}
/* find index of nearest low sampling point */
unsigned min_lat_index = (-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES;
unsigned min_lon_index = (-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES;
/* find index of nearest low sampling point */
unsigned min_lat_index = (-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES;
unsigned min_lon_index = (-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES;
float declination_sw = get_lookup_table_val(min_lat_index, min_lon_index);
float declination_se = get_lookup_table_val(min_lat_index, min_lon_index + 1);
float declination_ne = get_lookup_table_val(min_lat_index + 1, min_lon_index + 1);
float declination_nw = get_lookup_table_val(min_lat_index + 1, min_lon_index);
float declination_sw = get_lookup_table_val(min_lat_index, min_lon_index);
float declination_se = get_lookup_table_val(min_lat_index, min_lon_index + 1);
float declination_ne = get_lookup_table_val(min_lat_index + 1, min_lon_index + 1);
float declination_nw = get_lookup_table_val(min_lat_index + 1, min_lon_index);
/* perform bilinear interpolation on the four grid corners */
/* perform bilinear interpolation on the four grid corners */
float declination_min = ((lon - min_lon) / SAMPLING_RES) * (declination_se - declination_sw) + declination_sw;
float declination_max = ((lon - min_lon) / SAMPLING_RES) * (declination_ne - declination_nw) + declination_nw;
float declination_min = ((lon - min_lon) / SAMPLING_RES) * (declination_se - declination_sw) + declination_sw;
float declination_max = ((lon - min_lon) / SAMPLING_RES) * (declination_ne - declination_nw) + declination_nw;
return ((lat - min_lat) / SAMPLING_RES) * (declination_max - declination_min) + declination_min;
return ((lat - min_lat) / SAMPLING_RES) * (declination_max - declination_min) + declination_min;
}
#endif

View file

@ -170,7 +170,7 @@ typedef struct beeperTableEntry_s {
{ BEEPER_ENTRY(BEEPER_SYSTEM_INIT, 16, NULL, "SYSTEM_INIT") },
{ BEEPER_ENTRY(BEEPER_USB, 17, NULL, "ON_USB") },
{ BEEPER_ENTRY(BEEPER_ALL, 18, NULL, "ALL") },
{ BEEPER_ENTRY(BEEPER_ALL, 18, NULL, "ALL") },
{ BEEPER_ENTRY(BEEPER_PREFERENCE, 19, NULL, "PREFERED") },
};
@ -306,7 +306,7 @@ void beeperUpdate(void)
if (!beeperIsOn) {
beeperIsOn = 1;
if (currentBeeperEntry->sequence[beeperPos] != 0) {
if (!(getBeeperOffMask() & (1 << (currentBeeperEntry->mode - 1))))
if (!(getBeeperOffMask() & (1 << (currentBeeperEntry->mode - 1))))
BEEP_ON;
warningLedEnable();

View file

@ -29,7 +29,7 @@ typedef enum {
BEEPER_ARMING_GPS_FIX, // Beep a special tone when arming the board and GPS has fix
BEEPER_BAT_CRIT_LOW, // Longer warning beeps when battery is critically low (repeats)
BEEPER_BAT_LOW, // Warning beeps when battery is getting low (repeats)
BEEPER_GPS_STATUS, // FIXME **** Disable beeper when connected to USB ****
BEEPER_GPS_STATUS, // FIXME **** Disable beeper when connected to USB ****
BEEPER_RX_SET, // Beeps when aux channel is set for beep or beep sequence how many satellites has found if GPS enabled
BEEPER_DISARM_REPEAT, // Beeps sounded while stick held in disarm position
BEEPER_ACC_CALIBRATION, // ACC inflight calibration completed confirmation

View file

@ -73,7 +73,7 @@ typedef struct {
uint16_t pdop; // 40
uint16_t vdop; // 42
uint16_t ndop; // 44
uint16_t edop; // 46
uint16_t edop; // 46
uint8_t satellites; // 48
uint8_t reserved3; //
uint8_t fix_type; // 50
@ -81,7 +81,7 @@ typedef struct {
uint8_t fix_status; // 52
uint8_t reserved5;
uint8_t reserved6;
uint8_t mask; // 55
uint8_t mask; // 55
} naza_nav;
enum {

View file

@ -120,7 +120,7 @@ static const uint8_t ubloxInit_RATE_5Hz[] = {
#ifdef GPS_PROTO_UBLOX_NEO7PLUS
static const uint8_t ubloxInit_RATE_10Hz[] = {
0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0x64, 0x00, 0x01, 0x00, 0x01, 0x00, 0x7A, 0x12, // set rate to 10Hz (measurement period: 100ms, navigation rate: 1 cycle)
0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0x64, 0x00, 0x01, 0x00, 0x01, 0x00, 0x7A, 0x12, // set rate to 10Hz (measurement period: 100ms, navigation rate: 1 cycle)
};
#endif

View file

@ -257,16 +257,16 @@ const ledConfig_t defaultLedStripConfig[] = {
};
#elif defined(USE_COLIBTI_RACE_LED_DEFAULT_CONFIG)
const ledConfig_t defaultLedStripConfig[] = {
{ CALCULATE_LED_XY( 0, 0), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 0, 1), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 0, 8), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 7, 15), 6, LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 8, 15), 6, LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 7, 14), 6, LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 8, 14), 6, LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 15, 8), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 15, 1), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 15, 0), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 0, 0), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 0, 1), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 0, 8), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 7, 15), 6, LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 8, 15), 6, LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 7, 14), 6, LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 8, 14), 6, LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 15, 8), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 15, 1), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
{ CALCULATE_LED_XY( 15, 0), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR },
};
#else
const ledConfig_t defaultLedStripConfig[] = {
@ -1268,6 +1268,6 @@ static void ledStripDisable(void)
{
setStripColor(&HSV(BLACK));
ws2811UpdateStrip();
ws2811UpdateStrip();
}
#endif

View file

@ -90,7 +90,7 @@ static uint8_t ckSumOut;
static void StkSendByte(uint8_t dat)
{
ckSumOut ^= dat;
for (uint8_t i = 0; i < 8; i++) {
for (uint8_t i = 0; i < 8; i++) {
if (dat & 0x01) {
// 1-bits are encoded as 64.0us high, 72.8us low (135.8us total).
ESC_SET_HI;
@ -249,9 +249,9 @@ static uint8_t _CMD_SPI_MULTI_EX(uint8_t * resByte, uint8_t subcmd, uint16_t add
StkSendByte(4); // NumTX
StkSendByte(4); // NumRX
StkSendByte(0); // RxStartAdr
StkSendByte(subcmd); // {TxData} Cmd
StkSendByte(subcmd); // {TxData} Cmd
StkSendByte(addr >> 8); // {TxData} AdrHi
StkSendByte(addr & 0xff); // {TxData} AdrLow
StkSendByte(addr & 0xff); // {TxData} AdrLow
StkSendByte(0); // {TxData} 0
StkSendPacketFooter();
if (StkRcvPacket(stkInBuf, sizeof(stkInBuf))) { // NumRX + 3

View file

@ -67,7 +67,7 @@
// 2200µs -> 0xFFF
// Total range is: 2200 - 800 = 1400 <==> 4095
// Use formula: 800 + value * 1400 / 4096 (i.e. a shift by 12)
#define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12))
#define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12))
static bool xBusFrameReceived = false;
static bool xBusDataIncoming = false;

View file

@ -93,7 +93,7 @@ typedef enum {
} barometerState_e;
bool isBaroReady(void) {
return baroReady;
return baroReady;
}
uint32_t baroUpdate(void)

View file

@ -507,7 +507,7 @@ static void detectBaro(baroSensor_e baroHardwareToUse)
break;
}
#endif
; // fallthough
; // fallthough
case BARO_BMP280:
#ifdef USE_BARO_BMP280
if (bmp280Detect(&baro)) {

View file

@ -424,8 +424,8 @@ static void hottCheckSerialData(uint32_t currentMicros)
}
static void workAroundForHottTelemetryOnUsart(serialPort_t *instance, portMode_t mode) {
closeSerialPort(hottPort);
hottPort = openSerialPort(instance->identifier, FUNCTION_TELEMETRY_HOTT, NULL, HOTT_BAUDRATE, mode, SERIAL_NOT_INVERTED);
closeSerialPort(hottPort);
hottPort = openSerialPort(instance->identifier, FUNCTION_TELEMETRY_HOTT, NULL, HOTT_BAUDRATE, mode, SERIAL_NOT_INVERTED);
}
static void hottSendTelemetryData(void) {
@ -433,9 +433,9 @@ static void hottSendTelemetryData(void) {
hottIsSending = true;
// FIXME temorary workaround for HoTT not working on Hardware serial ports due to hardware/softserial serial port initialisation differences
if ((portConfig->identifier == SERIAL_PORT_USART1) || (portConfig->identifier == SERIAL_PORT_USART2) || (portConfig->identifier == SERIAL_PORT_USART3))
workAroundForHottTelemetryOnUsart(hottPort, MODE_TX);
workAroundForHottTelemetryOnUsart(hottPort, MODE_TX);
else
serialSetMode(hottPort, MODE_TX);
serialSetMode(hottPort, MODE_TX);
hottMsgCrc = 0;
return;
}
@ -445,9 +445,9 @@ static void hottSendTelemetryData(void) {
hottIsSending = false;
// FIXME temorary workaround for HoTT not working on Hardware serial ports due to hardware/softserial serial port initialisation differences
if ((portConfig->identifier == SERIAL_PORT_USART1) || (portConfig->identifier == SERIAL_PORT_USART2) || (portConfig->identifier == SERIAL_PORT_USART3))
workAroundForHottTelemetryOnUsart(hottPort, MODE_RX);
workAroundForHottTelemetryOnUsart(hottPort, MODE_RX);
else
serialSetMode(hottPort, MODE_RX);
serialSetMode(hottPort, MODE_RX);
flushHottRxBuffer();
return;
}

View file

@ -65,8 +65,8 @@ CDC_IF_Prop_TypeDef VCP_fops = {VCP_Init, VCP_DeInit, VCP_Ctrl, VCP_DataTx, VCP_
*/
static uint16_t VCP_Init(void)
{
bDeviceState = CONFIGURED;
return USBD_OK;
bDeviceState = CONFIGURED;
return USBD_OK;
}
/**
@ -77,8 +77,8 @@ static uint16_t VCP_Init(void)
*/
static uint16_t VCP_DeInit(void)
{
bDeviceState = UNCONNECTED;
return USBD_OK;
bDeviceState = UNCONNECTED;
return USBD_OK;
}
void ust_cpy(LINE_CODING* plc2, const LINE_CODING* plc1)