mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: remove unnecessary check of flight mode from fence response
This commit is contained in:
parent
d86ac9041e
commit
8e62035328
@ -39,14 +39,12 @@ void fence_check()
|
||||
if (GPS_ok()) {
|
||||
// if we are within 100m of the fence, RTL
|
||||
if( fence.get_breach_distance(new_breaches) <= AC_FENCE_GIVE_UP_DISTANCE) {
|
||||
if(control_mode != RTL) {
|
||||
set_mode(RTL);
|
||||
if (!set_mode(RTL)) {
|
||||
set_mode(LAND);
|
||||
}
|
||||
}else{
|
||||
// if more than 100m outside the fence just force a land
|
||||
if(control_mode != LAND) {
|
||||
set_mode(LAND);
|
||||
}
|
||||
set_mode(LAND);
|
||||
}
|
||||
}else{
|
||||
// we have no GPS so LAND
|
||||
|
Loading…
Reference in New Issue
Block a user