mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
Changed tabs to spaces in io/
This commit is contained in:
parent
93069233c9
commit
3a0f8388ee
12 changed files with 94 additions and 94 deletions
|
@ -172,7 +172,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, "PREFERRED") },
|
||||
};
|
||||
|
||||
|
@ -308,7 +308,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();
|
||||
warningLedRefresh();
|
||||
|
|
|
@ -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
|
||||
|
@ -40,7 +40,7 @@ typedef enum {
|
|||
BEEPER_SYSTEM_INIT, // Initialisation beeps when board is powered on
|
||||
BEEPER_USB, // Some boards have beeper powered USB connected
|
||||
|
||||
BEEPER_ALL, // Turn ON or OFF all beeper conditions
|
||||
BEEPER_ALL, // Turn ON or OFF all beeper conditions
|
||||
BEEPER_PREFERENCE, // Save prefered beeper configuration
|
||||
// BEEPER_ALL and BEEPER_PREFERENCE must remain at the bottom of this enum
|
||||
} beeperMode_e;
|
||||
|
|
|
@ -239,7 +239,7 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig)
|
|||
// only RX is needed for NMEA-style GPS
|
||||
#if !defined(COLIBRI_RACE) || !defined(LUX_RACE)
|
||||
if (gpsConfig->provider == GPS_NMEA)
|
||||
mode &= ~MODE_TX;
|
||||
mode &= ~MODE_TX;
|
||||
#endif
|
||||
|
||||
// no callback - buffer will be consumed in gpsThread()
|
||||
|
@ -256,47 +256,47 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig)
|
|||
void gpsInitNmea(void)
|
||||
{
|
||||
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
|
||||
uint32_t now;
|
||||
uint32_t now;
|
||||
#endif
|
||||
switch(gpsData.state) {
|
||||
case GPS_INITIALIZING:
|
||||
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
|
||||
now = millis();
|
||||
if (now - gpsData.state_ts < 1000)
|
||||
return;
|
||||
gpsData.state_ts = now;
|
||||
if (gpsData.state_position < 1) {
|
||||
serialSetBaudRate(gpsPort, 4800);
|
||||
gpsData.state_position++;
|
||||
} else if (gpsData.state_position < 2) {
|
||||
// print our FIXED init string for the baudrate we want to be at
|
||||
serialPrint(gpsPort, "$PSRF100,1,115200,8,1,0*05\r\n");
|
||||
gpsData.state_position++;
|
||||
} else {
|
||||
// we're now (hopefully) at the correct rate, next state will switch to it
|
||||
gpsSetState(GPS_CHANGE_BAUD);
|
||||
}
|
||||
break;
|
||||
now = millis();
|
||||
if (now - gpsData.state_ts < 1000)
|
||||
return;
|
||||
gpsData.state_ts = now;
|
||||
if (gpsData.state_position < 1) {
|
||||
serialSetBaudRate(gpsPort, 4800);
|
||||
gpsData.state_position++;
|
||||
} else if (gpsData.state_position < 2) {
|
||||
// print our FIXED init string for the baudrate we want to be at
|
||||
serialPrint(gpsPort, "$PSRF100,1,115200,8,1,0*05\r\n");
|
||||
gpsData.state_position++;
|
||||
} else {
|
||||
// we're now (hopefully) at the correct rate, next state will switch to it
|
||||
gpsSetState(GPS_CHANGE_BAUD);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
case GPS_CHANGE_BAUD:
|
||||
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
|
||||
now = millis();
|
||||
if (now - gpsData.state_ts < 1000)
|
||||
return;
|
||||
gpsData.state_ts = now;
|
||||
if (gpsData.state_position < 1) {
|
||||
serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]);
|
||||
gpsData.state_position++;
|
||||
} else if (gpsData.state_position < 2) {
|
||||
serialPrint(gpsPort, "$PSRF103,00,6,00,0*23\r\n");
|
||||
gpsData.state_position++;
|
||||
} else {
|
||||
now = millis();
|
||||
if (now - gpsData.state_ts < 1000)
|
||||
return;
|
||||
gpsData.state_ts = now;
|
||||
if (gpsData.state_position < 1) {
|
||||
serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]);
|
||||
gpsData.state_position++;
|
||||
} else if (gpsData.state_position < 2) {
|
||||
serialPrint(gpsPort, "$PSRF103,00,6,00,0*23\r\n");
|
||||
gpsData.state_position++;
|
||||
} else {
|
||||
#else
|
||||
serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]);
|
||||
#endif
|
||||
gpsSetState(GPS_RECEIVING_DATA);
|
||||
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
|
||||
}
|
||||
}
|
||||
#endif
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -273,16 +273,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[] = {
|
||||
|
@ -370,8 +370,8 @@ static const uint16_t functionMappings[FUNCTION_COUNT] = {
|
|||
LED_FUNCTION_FLIGHT_MODE,
|
||||
LED_FUNCTION_ARM_STATE,
|
||||
LED_FUNCTION_THROTTLE,
|
||||
LED_FUNCTION_THRUST_RING,
|
||||
LED_FUNCTION_COLOR
|
||||
LED_FUNCTION_THRUST_RING,
|
||||
LED_FUNCTION_COLOR
|
||||
};
|
||||
|
||||
// grid offsets
|
||||
|
@ -938,7 +938,7 @@ static void applyLedAnimationLayer(void)
|
|||
void updateLedStrip(void)
|
||||
{
|
||||
|
||||
if (!(ledStripInitialised && isWS2811LedStripReady())) {
|
||||
if (!(ledStripInitialised && isWS2811LedStripReady())) {
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -1115,8 +1115,8 @@ void ledStripEnable(void)
|
|||
|
||||
static void ledStripDisable(void)
|
||||
{
|
||||
setStripColor(&hsv_black);
|
||||
setStripColor(&hsv_black);
|
||||
|
||||
ws2811UpdateStrip();
|
||||
ws2811UpdateStrip();
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -607,7 +607,7 @@ void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
|
|||
switch(adjustmentFunction) {
|
||||
case ADJUSTMENT_RATE_PROFILE:
|
||||
if (getCurrentControlRateProfile() != position) {
|
||||
changeControlRateProfile(position);
|
||||
changeControlRateProfile(position);
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RATE_PROFILE, position);
|
||||
applied = true;
|
||||
}
|
||||
|
|
|
@ -89,7 +89,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;
|
||||
|
@ -248,9 +248,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
|
||||
|
|
|
@ -2566,18 +2566,18 @@ static void cliRateProfile(char *cmdline) {
|
|||
|
||||
static void cliReboot(void)
|
||||
{
|
||||
cliRebootEx(false);
|
||||
cliRebootEx(false);
|
||||
}
|
||||
|
||||
static void cliRebootEx(bool bootLoader)
|
||||
{
|
||||
cliPrint("\r\nRebooting");
|
||||
cliPrint("\r\nRebooting");
|
||||
bufWriterFlush(cliWriter);
|
||||
waitForSerialPortToFinishTransmitting(cliPort);
|
||||
stopMotors();
|
||||
if (bootLoader) {
|
||||
systemResetToBootloader();
|
||||
return;
|
||||
systemResetToBootloader();
|
||||
return;
|
||||
}
|
||||
systemReset();
|
||||
}
|
||||
|
@ -3082,22 +3082,22 @@ static void cliResource(char *cmdline)
|
|||
const char* owner;
|
||||
owner = ownerNames[ioRecs[i].owner];
|
||||
|
||||
const char* resource;
|
||||
resource = resourceNames[ioRecs[i].resource];
|
||||
const char* resource;
|
||||
resource = resourceNames[ioRecs[i].resource];
|
||||
|
||||
if (ioRecs[i].index > 0) {
|
||||
cliPrintf("%c%02d: %s%d %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, ioRecs[i].index, resource);
|
||||
} else {
|
||||
cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, resource);
|
||||
if (ioRecs[i].index > 0) {
|
||||
cliPrintf("%c%02d: %s%d %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, ioRecs[i].index, resource);
|
||||
} else {
|
||||
cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, resource);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void cliDfu(char *cmdLine)
|
||||
{
|
||||
UNUSED(cmdLine);
|
||||
cliPrint("\r\nRestarting in DFU mode");
|
||||
cliRebootEx(true);
|
||||
UNUSED(cmdLine);
|
||||
cliPrint("\r\nRestarting in DFU mode");
|
||||
cliRebootEx(true);
|
||||
}
|
||||
|
||||
void cliInit(serialConfig_t *serialConfig)
|
||||
|
|
|
@ -76,7 +76,7 @@ static uint8_t locked = 0;
|
|||
|
||||
void vtxInit(void)
|
||||
{
|
||||
rtc6705Init();
|
||||
rtc6705Init();
|
||||
if (masterConfig.vtx_mode == 0) {
|
||||
rtc6705SetChannel(masterConfig.vtx_band, masterConfig.vtx_channel);
|
||||
} else if (masterConfig.vtx_mode == 1) {
|
||||
|
|
|
@ -17,11 +17,11 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define VTX_BAND_MIN 1
|
||||
#define VTX_BAND_MAX 5
|
||||
#define VTX_CHANNEL_MIN 1
|
||||
#define VTX_CHANNEL_MAX 8
|
||||
#define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10
|
||||
#define VTX_BAND_MIN 1
|
||||
#define VTX_BAND_MAX 5
|
||||
#define VTX_CHANNEL_MIN 1
|
||||
#define VTX_CHANNEL_MAX 8
|
||||
#define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10
|
||||
|
||||
typedef struct vtxChannelActivationCondition_s {
|
||||
uint8_t auxChannelIndex;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue