mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: add disarm on land detect option to PILOT_THR_BHV
This commit is contained in:
parent
cfb2a6b2f9
commit
747344a8ba
@ -97,8 +97,8 @@ const AP_Param::Info Copter::var_info[] = {
|
||||
// @DisplayName: Throttle stick behavior
|
||||
// @Description: Bitmask containing various throttle stick options. Add up the values for options that you want.
|
||||
// @User: Standard
|
||||
// @Values: 0:None,1:Feedback from mid stick,2:High throttle cancels landing
|
||||
// @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing
|
||||
// @Values: 0:None,1:Feedback from mid stick,2:High throttle cancels landing,4:Disarm on land detection
|
||||
// @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection
|
||||
GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0),
|
||||
|
||||
// @Group: SERIAL
|
||||
|
@ -461,3 +461,4 @@ enum ThrowModeState {
|
||||
// for PILOT_THR_BHV parameter
|
||||
#define THR_BEHAVE_FEEDBACK_FROM_MID_STICK (1<<0)
|
||||
#define THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND (1<<1)
|
||||
#define THR_BEHAVE_DISARM_ON_LAND_DETECT (1<<2)
|
||||
|
@ -93,6 +93,13 @@ void Copter::set_land_complete(bool b)
|
||||
Log_Write_Event(DATA_NOT_LANDED);
|
||||
}
|
||||
ap.land_complete = b;
|
||||
|
||||
bool disarm_on_land_configured = (g.throttle_behavior & THR_BEHAVE_DISARM_ON_LAND_DETECT) != 0;
|
||||
bool mode_disarms_on_land = mode_allows_arming(control_mode,false) && !mode_has_manual_throttle(control_mode);
|
||||
|
||||
if (ap.land_complete && motors.armed() && disarm_on_land_configured && mode_disarms_on_land) {
|
||||
init_disarm_motors();
|
||||
}
|
||||
}
|
||||
|
||||
// set land complete maybe flag
|
||||
|
Loading…
Reference in New Issue
Block a user