mirror of https://github.com/ArduPilot/ardupilot
Plane: only disable fences when in landing phase
This commit is contained in:
parent
8c0c84b7ab
commit
e4cbee133b
|
@ -13,7 +13,7 @@ void Plane::fence_check()
|
||||||
bool is_in_landing = plane.flight_stage == AP_FixedWing::FlightStage::LAND
|
bool is_in_landing = plane.flight_stage == AP_FixedWing::FlightStage::LAND
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
|| control_mode->mode_number() == Mode::Number::QLAND
|
|| control_mode->mode_number() == Mode::Number::QLAND
|
||||||
|| control_mode->mode_number() == Mode::Number::QRTL
|
|| quadplane.in_vtol_land_descent()
|
||||||
#endif
|
#endif
|
||||||
|| (plane.is_land_command(mission_id) && plane.mission.state() == AP_Mission::MISSION_RUNNING);
|
|| (plane.is_land_command(mission_id) && plane.mission.state() == AP_Mission::MISSION_RUNNING);
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue