Copter: fence breach causes disarm if landed
Previously it would only disarm if the throttle was also at zero. Pair programmed with Tridge
This commit is contained in:
parent
26f7ab49e3
commit
7bd8d48809
@ -28,9 +28,9 @@ void fence_check()
|
|||||||
// if the user wants some kind of response and motors are armed
|
// if the user wants some kind of response and motors are armed
|
||||||
if(fence.get_action() != AC_FENCE_ACTION_REPORT_ONLY ) {
|
if(fence.get_action() != AC_FENCE_ACTION_REPORT_ONLY ) {
|
||||||
|
|
||||||
// disarm immediately if we think we are on the ground
|
// disarm immediately if we think we are on the ground or in a manual flight mode with zero throttle
|
||||||
// don't disarm if the high-altitude fence has been broken because it's likely the user has pulled their throttle to zero to bring it down
|
// don't disarm if the high-altitude fence has been broken because it's likely the user has pulled their throttle to zero to bring it down
|
||||||
if(ap.land_complete || manual_flight_mode(control_mode) && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0)){
|
if (ap.land_complete || (manual_flight_mode(control_mode) && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0))){
|
||||||
init_disarm_motors();
|
init_disarm_motors();
|
||||||
}else{
|
}else{
|
||||||
// if we are within 100m of the fence, RTL
|
// if we are within 100m of the fence, RTL
|
||||||
|
Loading…
Reference in New Issue
Block a user