Plane: Prevent FS action overiding VTOL land

This commit is contained in:
Gone4Dirt 2019-12-27 21:13:27 +00:00 committed by Randy Mackay
parent 90d15af4ae
commit ce963c8f0f
3 changed files with 14 additions and 1 deletions

View File

@ -171,7 +171,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
}
FALLTHROUGH;
case Failsafe_Action_RTL:
if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND && control_mode != &mode_qland ) {
if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND && control_mode != &mode_qland && !quadplane.in_vtol_land_sequence()) {
// never stop a landing if we were already committed
set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE);
aparm.throttle_cruise.load();

View File

@ -3172,3 +3172,11 @@ bool QuadPlane::in_vtol_land_final(void) const
{
return in_vtol_land_descent() && poscontrol.state == QPOS_LAND_FINAL;
}
/*
see if we are in any of the phases of a VTOL landing
*/
bool QuadPlane::in_vtol_land_sequence(void) const
{
return in_vtol_land_approach() || in_vtol_land_descent() || in_vtol_land_final();
}

View File

@ -554,6 +554,11 @@ private:
*/
bool in_vtol_land_final(void) const;
/*
are we in any of the phases of a VTOL landing?
*/
bool in_vtol_land_sequence(void) const;
public:
void motor_test_output();
MAV_RESULT mavlink_motor_test_start(mavlink_channel_t chan, uint8_t motor_seq, uint8_t throttle_type,