mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Copter: only disable fences when in landing phase
This commit is contained in:
parent
b7ce3ff286
commit
8c0c84b7ab
@ -10,10 +10,7 @@ void Copter::fence_check()
|
|||||||
{
|
{
|
||||||
const uint8_t orig_breaches = fence.get_breaches();
|
const uint8_t orig_breaches = fence.get_breaches();
|
||||||
|
|
||||||
bool is_in_landing = flightmode->mode_number() == Mode::Number::LAND
|
bool is_in_landing = flightmode->is_landing() || ap.land_complete || !motors->armed();
|
||||||
|| flightmode->mode_number() == Mode::Number::RTL
|
|
||||||
|| flightmode->mode_number() == Mode::Number::SMART_RTL
|
|
||||||
|| ap.land_complete || !motors->armed();
|
|
||||||
|
|
||||||
// check for new breaches; new_breaches is bitmask of fence types breached
|
// check for new breaches; new_breaches is bitmask of fence types breached
|
||||||
const uint8_t new_breaches = fence.check(is_in_landing);
|
const uint8_t new_breaches = fence.check(is_in_landing);
|
||||||
|
Loading…
Reference in New Issue
Block a user