Plane: Handle reset of q_fwd_throttle in QuadPlane::mode_enter(void)

This commit is contained in:
Paul Riseborough 2023-08-20 20:11:46 +10:00 committed by Andrew Tridgell
parent 2d3431a1ac
commit 98220c7315
9 changed files with 3 additions and 24 deletions

View File

@ -17,8 +17,6 @@ bool ModeAuto::_enter()
if (plane.quadplane.available() && plane.quadplane.enable == 2) {
plane.auto_state.vtol_mode = true;
// always zero forward throttle demand on entry into VTOL modes
quadplane.q_fwd_throttle = 0.0f;
} else {
plane.auto_state.vtol_mode = false;
}

View File

@ -5,9 +5,6 @@
bool ModeQAcro::_enter()
{
// always zero forward throttle demand on entry into VTOL modes
quadplane.q_fwd_throttle = 0.0f;
quadplane.throttle_wait = false;
quadplane.transition->force_transition_complete();
attitude_control->relax_attitude_controllers();

View File

@ -7,9 +7,6 @@
bool ModeQAutotune::_enter()
{
// always zero forward throttle demand on entry into VTOL modes
quadplane.q_fwd_throttle = 0.0f;
#if QAUTOTUNE_ENABLED
return quadplane.qautotune.init();
#else

View File

@ -5,9 +5,6 @@
bool ModeQHover::_enter()
{
// always zero forward throttle demand on entry into VTOL modes
quadplane.q_fwd_throttle = 0.0f;
// set vertical speed and acceleration limits
pos_control->set_max_speed_accel_z(-quadplane.get_pilot_velocity_z_max_dn(), quadplane.pilot_velocity_z_max_up, quadplane.pilot_accel_z);
pos_control->set_correction_speed_accel_z(-quadplane.get_pilot_velocity_z_max_dn(), quadplane.pilot_velocity_z_max_up, quadplane.pilot_accel_z);

View File

@ -5,9 +5,6 @@
bool ModeQLand::_enter()
{
// always zero forward throttle demand on entry into VTOL modes
quadplane.q_fwd_throttle = 0.0f;
plane.mode_qloiter._enter();
quadplane.throttle_wait = false;
quadplane.setup_target_position();

View File

@ -5,9 +5,6 @@
bool ModeQLoiter::_enter()
{
// always zero forward throttle demand on entry into VTOL modes
quadplane.q_fwd_throttle = 0.0f;
// initialise loiter
loiter_nav->clear_pilot_desired_acceleration();
loiter_nav->init_target();

View File

@ -5,9 +5,6 @@
bool ModeQRTL::_enter()
{
// always zero forward throttle demand on entry into VTOL modes
plane.quadplane.q_fwd_throttle = 0.0f;
// treat QRTL as QLAND if we are in guided wait takeoff state, to cope
// with failsafes during GUIDED->AUTO takeoff sequence
if (plane.quadplane.guided_wait_takeoff_on_mode_enter) {

View File

@ -5,9 +5,6 @@
bool ModeQStabilize::_enter()
{
// always zero forward throttle demand on entry into VTOL modes
quadplane.q_fwd_throttle = 0.0f;
quadplane.throttle_wait = false;
return true;
}

View File

@ -2088,7 +2088,7 @@ bool QuadPlane::handle_do_vtol_transition(enum MAV_VTOL_STATE state) const
gcs().send_text(MAV_SEVERITY_NOTICE, "Entered VTOL mode");
}
plane.auto_state.vtol_mode = true;
// always zero forward throttle demand on entry into VTOL modes
// This is a precaustion. It should be looked after by the call to QuadPlane::mode_enter(void) on mode entry.
plane.quadplane.q_fwd_throttle = 0.0f;
return true;
@ -4511,6 +4511,8 @@ void QuadPlane::mode_enter(void)
// state for special behaviour
guided_wait_takeoff_on_mode_enter = guided_wait_takeoff;
guided_wait_takeoff = false;
q_fwd_throttle = 0.0f;
}
// Set attitude control yaw rate time constant to pilot input command model value