mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
Add option for gyro calibration on first arm // Remove Retarded Arm
This commit is contained in:
parent
7e4c64056d
commit
4ec5166c0f
6 changed files with 10 additions and 20 deletions
|
@ -130,7 +130,7 @@ rollPitchStatus_e calculateRollPitchCenterStatus(rxConfig_t *rxConfig)
|
|||
return NOT_CENTERED;
|
||||
}
|
||||
|
||||
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, bool retarded_arm, bool disarm_kill_switch)
|
||||
void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStatus, bool disarm_kill_switch)
|
||||
{
|
||||
static uint8_t rcDelayCommand; // this indicates the number of time (multiple of RC measurement at 50Hz) the sticks must be maintained to run or switch off motors
|
||||
static uint8_t rcSticks; // this hold sticks position for command combos
|
||||
|
@ -195,15 +195,6 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat
|
|||
rcDelayCommand = 0; // reset so disarm tone will repeat
|
||||
}
|
||||
}
|
||||
// Disarm on roll (only when retarded_arm is enabled)
|
||||
if (retarded_arm && (rcSticks == THR_LO + YAW_CE + PIT_CE + ROL_LO)) {
|
||||
if (ARMING_FLAG(ARMED))
|
||||
mwDisarm();
|
||||
else {
|
||||
beeper(BEEPER_DISARM_REPEAT); // sound tone while stick held
|
||||
rcDelayCommand = 0; // reset so disarm tone will repeat
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
|
@ -261,12 +252,6 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat
|
|||
mwArm();
|
||||
return;
|
||||
}
|
||||
|
||||
if (retarded_arm && (rcSticks == THR_LO + YAW_CE + PIT_CE + ROL_HI)) {
|
||||
// Arm via ROLL
|
||||
mwArm();
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
if (rcSticks == THR_HI + YAW_LO + PIT_LO + ROL_CE) {
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue