mirror of https://github.com/ArduPilot/ardupilot
Plane: disable fences for landing by suppressing in the fence check rather than using a state machine
This commit is contained in:
parent
04dd7de1ed
commit
46d6d0bf03
|
@ -434,10 +434,6 @@ void Plane::do_land(const AP_Mission::Mission_Command& cmd)
|
||||||
// if we were in an abort we need to explicitly move out of the abort state, as it's sticky
|
// if we were in an abort we need to explicitly move out of the abort state, as it's sticky
|
||||||
set_flight_stage(AP_FixedWing::FlightStage::LAND);
|
set_flight_stage(AP_FixedWing::FlightStage::LAND);
|
||||||
}
|
}
|
||||||
|
|
||||||
#if AP_FENCE_ENABLED
|
|
||||||
plane.fence.auto_disable_fence_for_landing();
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HAL_QUADPLANE_ENABLED
|
#if HAL_QUADPLANE_ENABLED
|
||||||
|
|
|
@ -9,8 +9,16 @@ void Plane::fence_check()
|
||||||
{
|
{
|
||||||
const uint8_t orig_breaches = fence.get_breaches();
|
const uint8_t orig_breaches = fence.get_breaches();
|
||||||
|
|
||||||
|
uint16_t mission_id = plane.mission.get_current_nav_cmd().id;
|
||||||
|
bool is_in_landing = plane.flight_stage == AP_FixedWing::FlightStage::LAND
|
||||||
|
#if HAL_QUADPLANE_ENABLED
|
||||||
|
|| control_mode->mode_number() == Mode::Number::QLAND
|
||||||
|
|| control_mode->mode_number() == Mode::Number::QRTL
|
||||||
|
#endif
|
||||||
|
|| (plane.is_land_command(mission_id) && plane.mission.state() == AP_Mission::MISSION_RUNNING);
|
||||||
|
|
||||||
// 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();
|
const uint8_t new_breaches = fence.check(is_in_landing);
|
||||||
|
|
||||||
if (!fence.enabled()) {
|
if (!fence.enabled()) {
|
||||||
// Switch back to the chosen control mode if still in
|
// Switch back to the chosen control mode if still in
|
||||||
|
|
|
@ -54,10 +54,6 @@ void ModeAuto::_exit()
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
if (restart) {
|
if (restart) {
|
||||||
#if AP_FENCE_ENABLED
|
|
||||||
// no longer landing to re-enable the possiblity of the fence floor
|
|
||||||
plane.fence.reset_fence_floor_enable();
|
|
||||||
#endif
|
|
||||||
plane.landing.restart_landing_sequence();
|
plane.landing.restart_landing_sequence();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -16,9 +16,6 @@ bool ModeQLand::_enter()
|
||||||
#if AP_LANDINGGEAR_ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
plane.g2.landing_gear.deploy_for_landing();
|
plane.g2.landing_gear.deploy_for_landing();
|
||||||
#endif
|
#endif
|
||||||
#if AP_FENCE_ENABLED
|
|
||||||
plane.fence.auto_disable_fence_for_landing();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
|
@ -3554,9 +3554,6 @@ bool QuadPlane::verify_vtol_land(void)
|
||||||
poscontrol.pilot_correction_done = false;
|
poscontrol.pilot_correction_done = false;
|
||||||
pos_control->set_lean_angle_max_cd(0);
|
pos_control->set_lean_angle_max_cd(0);
|
||||||
poscontrol.xy_correction.zero();
|
poscontrol.xy_correction.zero();
|
||||||
#if AP_FENCE_ENABLED
|
|
||||||
plane.fence.auto_disable_fence_for_landing();
|
|
||||||
#endif
|
|
||||||
#if AP_LANDINGGEAR_ENABLED
|
#if AP_LANDINGGEAR_ENABLED
|
||||||
plane.g2.landing_gear.deploy_for_landing();
|
plane.g2.landing_gear.deploy_for_landing();
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue