mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 06:15:16 +03:00
Minor whitespace tidy
This commit is contained in:
parent
9653249716
commit
555475ec95
3 changed files with 138 additions and 138 deletions
|
@ -696,17 +696,17 @@ void subTaskMainSubprocesses(void)
|
|||
gyro.dev.temperature(&telemTemperature1);
|
||||
}
|
||||
|
||||
#ifdef MAG
|
||||
#ifdef MAG
|
||||
if (sensors(SENSOR_MAG)) {
|
||||
updateMagHold();
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef GTUNE
|
||||
#ifdef GTUNE
|
||||
updateGtuneState();
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(BARO) || defined(SONAR)
|
||||
#if defined(BARO) || defined(SONAR)
|
||||
// updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState
|
||||
updateRcCommands();
|
||||
if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) {
|
||||
|
@ -714,20 +714,20 @@ void subTaskMainSubprocesses(void)
|
|||
applyAltHold(&masterConfig.airplaneConfig);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// If we're armed, at minimum throttle, and we do arming via the
|
||||
// sticks, do not process yaw input from the rx. We do this so the
|
||||
// motors do not spin up while we are trying to arm or disarm.
|
||||
// Allow yaw control for tricopters if the user wants the servo to move even when unarmed.
|
||||
if (isUsingSticksForArming() && rcData[THROTTLE] <= rxConfig()->mincheck
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
#ifdef USE_SERVOS
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
#ifdef USE_SERVOS
|
||||
&& !((mixerConfig()->mixerMode == MIXER_TRI || mixerConfig()->mixerMode == MIXER_CUSTOM_TRI) && servoMixerConfig()->tri_unarmed_servo)
|
||||
#endif
|
||||
#endif
|
||||
&& mixerConfig()->mixerMode != MIXER_AIRPLANE
|
||||
&& mixerConfig()->mixerMode != MIXER_FLYING_WING
|
||||
#endif
|
||||
#endif
|
||||
) {
|
||||
rcCommand[YAW] = 0;
|
||||
setpointRate[YAW] = 0;
|
||||
|
@ -739,27 +739,27 @@ void subTaskMainSubprocesses(void)
|
|||
|
||||
processRcCommand();
|
||||
|
||||
#ifdef GPS
|
||||
#ifdef GPS
|
||||
if (sensors(SENSOR_GPS)) {
|
||||
if ((FLIGHT_MODE(GPS_HOME_MODE) || FLIGHT_MODE(GPS_HOLD_MODE)) && STATE(GPS_FIX_HOME)) {
|
||||
updateGpsStateForHomeAndHoldMode();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef USE_SDCARD
|
||||
#ifdef USE_SDCARD
|
||||
afatfs_poll();
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef BLACKBOX
|
||||
#ifdef BLACKBOX
|
||||
if (!cliMode && feature(FEATURE_BLACKBOX)) {
|
||||
handleBlackbox(startTime);
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef TRANSPONDER
|
||||
#ifdef TRANSPONDER
|
||||
transponderUpdate(startTime);
|
||||
#endif
|
||||
#endif
|
||||
DEBUG_SET(DEBUG_PIDLOOP, 2, micros() - startTime);
|
||||
}
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue