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

Fixed missing spaces after 'if'.

This commit is contained in:
mikeller 2020-01-26 13:14:25 +13:00
parent 6497830a1b
commit ab025b76a8
10 changed files with 11 additions and 11 deletions

View file

@ -60,7 +60,7 @@ static void cmsx_Vtx_ConfigRead(void)
vtxCommonGetBandAndChannel(vtxCommonDevice(), &cmsx_vtxBand, &cmsx_vtxChannel);
vtxCommonGetPowerIndex(vtxCommonDevice(), &cmsx_vtxPower);
unsigned status;
if(vtxCommonGetStatus(vtxCommonDevice(), &status)){
if (vtxCommonGetStatus(vtxCommonDevice(), &status)) {
cmsx_vtxPit = status & VTX_STATUS_PIT_MODE ? 2 : 1;
} else {
cmsx_vtxPit = 0;

View file

@ -153,7 +153,7 @@ static int32_t BMI160_Config(const busDevice_t *bus)
// Verify that normal power mode was entered
uint8_t pmu_status = spiBusReadRegister(bus, BMI160_REG_PMU_STAT);
if ((pmu_status & 0x3C) != 0x14){
if ((pmu_status & 0x3C) != 0x14) {
return -3;
}

View file

@ -316,7 +316,7 @@ static SD_Error_t SD_CmdResponse(uint8_t SD_CMD, int8_t ResponseType)
if(ResponseType <= 0)
{
if(TimeOut == 0){
if (TimeOut == 0) {
return SD_CMD_RSP_TIMEOUT;
} else {
return SD_OK;

View file

@ -760,7 +760,7 @@ static serialPort_t *openEscSerial(const motorDevConfig_t *motorConfig, escSeria
setTxSignalEsc(escSerial, ENABLE);
serialTimerTxConfigBL(escSerial->txTimerHardware, portIndex, baud);
}
else if (mode == PROTOCOL_CASTLE){
else if (mode == PROTOCOL_CASTLE) {
escSerialOutputPortConfig(escSerial->rxTimerHardware);
serialTimerTxConfigBL(escSerial->txTimerHardware, portIndex, baud);
serialTimerRxConfigBL(escSerial->rxTimerHardware, portIndex, options);

View file

@ -1008,7 +1008,7 @@ bool processRx(timeUs_t currentTimeUs)
DISABLE_FLIGHT_MODE(HEADFREE_MODE);
}
if (IS_RC_MODE_ACTIVE(BOXHEADADJ)) {
if (imuQuaternionHeadfreeOffsetSet()){
if (imuQuaternionHeadfreeOffsetSet()) {
beeper(BEEPER_RX_SET);
}
}

View file

@ -332,7 +332,7 @@ static void rescueAttainPosition()
const int16_t altitudeError = rescueState.intent.targetAltitudeCm - rescueState.sensor.currentAltitudeCm;
// P component
if (ABS(altitudeError) > 0 && ABS(altitudeError) < GPS_RESCUE_ZVELOCITY_THRESHOLD){
if (ABS(altitudeError) > 0 && ABS(altitudeError) < GPS_RESCUE_ZVELOCITY_THRESHOLD) {
scalingRate = (float)altitudeError / GPS_RESCUE_ZVELOCITY_THRESHOLD;
} else {
scalingRate = 1;

View file

@ -1444,7 +1444,7 @@ void FAST_CODE pidController(const pidProfile_t *pidProfile, timeUs_t currentTim
// -----calculate D component
// disable D if launch control is active
if ((pidCoefficient[axis].Kd > 0) && !launchControlActive){
if ((pidCoefficient[axis].Kd > 0) && !launchControlActive) {
// Divide rate change by dT to get differential (ie dr/dt).
// dT is fixed and calculated from the target PID loop time

View file

@ -311,7 +311,7 @@ static rx_spi_received_e flySky2AReadAndProcess(uint8_t *payload, const uint32_t
break;
}
if (!waitTx){
if (!waitTx) {
A7105Strobe(A7105_RX);
}
return result;

View file

@ -180,7 +180,7 @@ static uint8_t appendSmartPortData(uint8_t *buf)
uint8_t index;
for (index = 0; index < TELEMETRY_DATA_SIZE; index++) { // max 5 bytes in a frame
if (telemetryOutReader == telemetryOutWriter){ // no new data
if (telemetryOutReader == telemetryOutWriter) { // no new data
break;
}
buf[index] = telemetryOutBuffer[telemetryOutReader];
@ -370,7 +370,7 @@ rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const pro
FALLTHROUGH;
// here FS code could be
case STATE_DATA:
if (rxSpiGetExtiState() && (frameReceived == false)){
if (rxSpiGetExtiState() && (frameReceived == false)) {
uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
if (ccLen >= packetLength) {
cc2500ReadFifo(packet, packetLength);

View file

@ -286,7 +286,7 @@ TEST(LQTest, TestElement_LQ_SOURCE_NONE_VALUES)
displayPortTestPrint();
#endif
// then
if (testdigit >= 10){
if (testdigit >= 10) {
displayPortTestBufferSubstring(8, 1,"%c9", SYM_LINK_QUALITY);
}else{
displayPortTestBufferSubstring(8, 1,"%c%1d", SYM_LINK_QUALITY, testdigit - 1);