mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 22:35:23 +03:00
Merge branch 'feature-autodisarm' of https://github.com/ledvinap/cleanflight into ledvinap-feature-autodisarm
This commit is contained in:
commit
84b197d5f8
4 changed files with 18 additions and 0 deletions
|
@ -352,6 +352,7 @@ static void resetConf(void)
|
||||||
|
|
||||||
masterConfig.retarded_arm = 0;
|
masterConfig.retarded_arm = 0;
|
||||||
masterConfig.disarm_kill_switch = 1;
|
masterConfig.disarm_kill_switch = 1;
|
||||||
|
masterConfig.auto_disarm_delay = 5;
|
||||||
masterConfig.small_angle = 25;
|
masterConfig.small_angle = 25;
|
||||||
|
|
||||||
masterConfig.airplaneConfig.flaps_speed = 0;
|
masterConfig.airplaneConfig.flaps_speed = 0;
|
||||||
|
|
|
@ -63,6 +63,7 @@ typedef struct master_t {
|
||||||
|
|
||||||
uint8_t retarded_arm; // allow disarm/arm on throttle down + roll left/right
|
uint8_t retarded_arm; // allow disarm/arm on throttle down + roll left/right
|
||||||
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
|
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
|
||||||
|
uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
|
||||||
uint8_t small_angle;
|
uint8_t small_angle;
|
||||||
|
|
||||||
airplaneConfig_t airplaneConfig;
|
airplaneConfig_t airplaneConfig;
|
||||||
|
|
|
@ -236,6 +236,7 @@ const clivalue_t valueTable[] = {
|
||||||
|
|
||||||
{ "retarded_arm", VAR_UINT8 | MASTER_VALUE, &masterConfig.retarded_arm, 0, 1 },
|
{ "retarded_arm", VAR_UINT8 | MASTER_VALUE, &masterConfig.retarded_arm, 0, 1 },
|
||||||
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.disarm_kill_switch, 0, 1 },
|
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.disarm_kill_switch, 0, 1 },
|
||||||
|
{ "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, 0, 60 },
|
||||||
{ "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, 0, 180 },
|
{ "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, 0, 180 },
|
||||||
|
|
||||||
{ "flaps_speed", VAR_UINT8 | MASTER_VALUE, &masterConfig.airplaneConfig.flaps_speed, 0, 100 },
|
{ "flaps_speed", VAR_UINT8 | MASTER_VALUE, &masterConfig.airplaneConfig.flaps_speed, 0, 100 },
|
||||||
|
|
|
@ -91,6 +91,7 @@ uint16_t cycleTime = 0; // this is the number in micro second to achieve
|
||||||
int16_t headFreeModeHold;
|
int16_t headFreeModeHold;
|
||||||
|
|
||||||
int16_t telemTemperature1; // gyro sensor temperature
|
int16_t telemTemperature1; // gyro sensor temperature
|
||||||
|
static uint32_t disarmTime; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
|
||||||
|
|
||||||
extern uint8_t dynP8[3], dynI8[3], dynD8[3];
|
extern uint8_t dynP8[3], dynI8[3], dynD8[3];
|
||||||
extern failsafe_t *failsafe;
|
extern failsafe_t *failsafe;
|
||||||
|
@ -326,6 +327,8 @@ void mwArm(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
disarmTime = millis() + masterConfig.auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
|
||||||
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -493,6 +496,18 @@ void processRx(void)
|
||||||
resetErrorAngle();
|
resetErrorAngle();
|
||||||
resetErrorGyro();
|
resetErrorGyro();
|
||||||
}
|
}
|
||||||
|
// When armed and motors aren't spinning, disarm board after delay so users without buzzer won't lose fingers.
|
||||||
|
// mixTable constrains motor commands, so checking throttleStatus is enough
|
||||||
|
if (ARMING_FLAG(ARMED)
|
||||||
|
&& feature(FEATURE_MOTOR_STOP) && !STATE(FIXED_WING)
|
||||||
|
&& masterConfig.auto_disarm_delay != 0) {
|
||||||
|
if (throttleStatus == THROTTLE_LOW) {
|
||||||
|
if ((int32_t)(disarmTime - millis()) < 0) // delay is over
|
||||||
|
mwDisarm();
|
||||||
|
} else {
|
||||||
|
disarmTime = millis() + masterConfig.auto_disarm_delay * 1000; // extend delay
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
processRcStickPositions(&masterConfig.rxConfig, throttleStatus, masterConfig.retarded_arm, masterConfig.disarm_kill_switch);
|
processRcStickPositions(&masterConfig.rxConfig, throttleStatus, masterConfig.retarded_arm, masterConfig.disarm_kill_switch);
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue