Plane: Quadplane: add assistance reset method

This commit is contained in:
Iampete1 2024-02-24 23:35:12 +00:00 committed by Andrew Tridgell
parent 39c86a46e0
commit 8196c899e8
3 changed files with 28 additions and 8 deletions

View File

@ -1451,6 +1451,16 @@ float QuadPlane::desired_auto_yaw_rate_cds(void) const
return yaw_rate; return yaw_rate;
} }
// Assistance not needed, reset any state
void QuadPlane::VTOL_Assist::reset()
{
in_angle_assist = false;
angle_error_start_ms = 0;
in_alt_assist = false;
alt_error_start_ms = 0;
}
/* /*
return true if the quadplane should provide stability assistance return true if the quadplane should provide stability assistance
*/ */
@ -1458,8 +1468,7 @@ bool QuadPlane::VTOL_Assist::should_assist(float aspeed, bool have_airspeed)
{ {
if (!plane.arming.is_armed_and_safety_off() || (state == STATE::ASSIST_DISABLED) || quadplane.tailsitter.is_control_surface_tailsitter()) { if (!plane.arming.is_armed_and_safety_off() || (state == STATE::ASSIST_DISABLED) || quadplane.tailsitter.is_control_surface_tailsitter()) {
// disarmed or disabled by aux switch or because a control surface tailsitter // disarmed or disabled by aux switch or because a control surface tailsitter
in_angle_assist = false; reset();
angle_error_start_ms = 0;
return false; return false;
} }
@ -1468,22 +1477,19 @@ bool QuadPlane::VTOL_Assist::should_assist(float aspeed, bool have_airspeed)
|| plane.is_flying() ) ) { || plane.is_flying() ) ) {
// not in a flight mode and condition where it would be safe to turn on vertial lift motors // not in a flight mode and condition where it would be safe to turn on vertial lift motors
// skip this check for tailsitters because the forward and vertial motors are the same and are controled directly by throttle imput unlike other quadplanes // skip this check for tailsitters because the forward and vertial motors are the same and are controled directly by throttle imput unlike other quadplanes
in_angle_assist = false; reset();
angle_error_start_ms = 0;
return false; return false;
} }
if (state == STATE::FORCE_ENABLED) { if (state == STATE::FORCE_ENABLED) {
// force enabled, no need to check thresholds // force enabled, no need to check thresholds
in_angle_assist = false; reset();
angle_error_start_ms = 0;
return true; return true;
} }
if (speed <= 0) { if (speed <= 0) {
// disabled via speed threshold // disabled via speed threshold
in_angle_assist = false; reset();
angle_error_start_ms = 0;
return false; return false;
} }
@ -1790,6 +1796,9 @@ void SLT_Transition::VTOL_update()
transition_state = TRANSITION_AIRSPEED_WAIT; transition_state = TRANSITION_AIRSPEED_WAIT;
} }
last_throttle = motors->get_throttle(); last_throttle = motors->get_throttle();
// Keep assistance reset while not checking
quadplane.assist.reset();
} }
/* /*
@ -4567,6 +4576,9 @@ void SLT_Transition::force_transition_complete() {
transition_start_ms = 0; transition_start_ms = 0;
transition_low_airspeed_ms = 0; transition_low_airspeed_ms = 0;
set_last_fw_pitch(); set_last_fw_pitch();
// Keep assistance reset while not checking
quadplane.assist.reset();
} }
MAV_VTOL_STATE SLT_Transition::get_mav_vtol_state() const MAV_VTOL_STATE SLT_Transition::get_mav_vtol_state() const

View File

@ -335,6 +335,9 @@ private:
// check for assistance needed // check for assistance needed
bool should_assist(float aspeed, bool have_airspeed); bool should_assist(float aspeed, bool have_airspeed);
// Assistance not needed, reset any state
void reset();
// speed below which quad assistance is given // speed below which quad assistance is given
AP_Float speed; AP_Float speed;

View File

@ -894,6 +894,9 @@ void Tailsitter_Transition::VTOL_update()
vtol_limit_start_ms = now; vtol_limit_start_ms = now;
vtol_limit_initial_pitch = quadplane.ahrs_view->pitch_sensor; vtol_limit_initial_pitch = quadplane.ahrs_view->pitch_sensor;
} }
} else {
// Keep assistance reset while not checking
quadplane.assist.reset();
} }
restart(); restart();
} }
@ -1006,6 +1009,8 @@ void Tailsitter_Transition::force_transition_complete()
vtol_transition_start_ms = AP_HAL::millis(); vtol_transition_start_ms = AP_HAL::millis();
vtol_transition_initial_pitch = constrain_float(plane.nav_pitch_cd,-8500,8500); vtol_transition_initial_pitch = constrain_float(plane.nav_pitch_cd,-8500,8500);
fw_limit_start_ms = 0; fw_limit_start_ms = 0;
quadplane.assist.reset();
} }
MAV_VTOL_STATE Tailsitter_Transition::get_mav_vtol_state() const MAV_VTOL_STATE Tailsitter_Transition::get_mav_vtol_state() const