mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: Handle always land mode
This commit is contained in:
parent
e55369b1c8
commit
f78ffefd66
@ -30,13 +30,17 @@ void Copter::fence_check()
|
|||||||
// 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 || (flightmode->has_manual_throttle() && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0))){
|
if (ap.land_complete || (flightmode->has_manual_throttle() && ap.throttle_zero && !failsafe.radio && ((fence.get_breaches() & AC_FENCE_TYPE_ALT_MAX)== 0))){
|
||||||
init_disarm_motors();
|
init_disarm_motors();
|
||||||
}else{
|
|
||||||
// if we are within 100m of the fence, RTL
|
} else {
|
||||||
if (fence.get_breach_distance(new_breaches) <= AC_FENCE_GIVE_UP_DISTANCE) {
|
// if always land option mode is specified, land
|
||||||
|
if (fence.get_action() == AC_FENCE_ACTION_ALWAYS_LAND) {
|
||||||
|
set_mode(LAND, MODE_REASON_FENCE_BREACH);
|
||||||
|
} else if (fence.get_breach_distance(new_breaches) <= AC_FENCE_GIVE_UP_DISTANCE) {
|
||||||
if (!set_mode(RTL, MODE_REASON_FENCE_BREACH)) {
|
if (!set_mode(RTL, MODE_REASON_FENCE_BREACH)) {
|
||||||
set_mode(LAND, MODE_REASON_FENCE_BREACH);
|
set_mode(LAND, MODE_REASON_FENCE_BREACH);
|
||||||
|
// if we are within 100m of the fence, RTL
|
||||||
}
|
}
|
||||||
}else{
|
} else {
|
||||||
// if more than 100m outside the fence just force a land
|
// if more than 100m outside the fence just force a land
|
||||||
set_mode(LAND, MODE_REASON_FENCE_BREACH);
|
set_mode(LAND, MODE_REASON_FENCE_BREACH);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user