From e3ce7d966b34974d65edb0ad55062551072b4cea Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 8 Sep 2023 13:26:41 +1000 Subject: [PATCH] Plane: fixes from review --- ArduPlane/quadplane.cpp | 14 +++----------- ArduPlane/tiltrotor.cpp | 2 +- 2 files changed, 4 insertions(+), 12 deletions(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 33c1f62ce9..09cb3d9da0 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -518,7 +518,7 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Description: When forward throttle is being controlled by the Q_FWD_THR_GAIN parameter in Q modes, the vehicle forward (nose down) pitch rotation will be limited to the value specified by this parameter and the any additional forward acceleration required will be produced by use of the forward thrust motor(s) or tilting of moveable rotors. Larger values allow the vehicle to pitch more nose down. Set initially to the amount of nose down pitch required to remove wing lift. // @Units: degrees // @Range: 0.0 5.0 - // @Increment: 10 + // @Increment: 0.1 // @User: Standard AP_GROUPINFO("FWD_PIT_LIM", 36, QuadPlane, q_fwd_pitch_lim, 3.0f), @@ -662,8 +662,6 @@ bool QuadPlane::setup(void) return false; } - q_fwd_throttle = 0.0f; - /* cope with upgrade from old AP_Motors values for frame_class */ @@ -2095,7 +2093,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; - // This is a precaustion. It should be looked after by the call to QuadPlane::mode_enter(void) on mode entry. + // This is a precaution. 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; @@ -3648,13 +3646,7 @@ void QuadPlane::Log_Write_QControl_Tuning() float QuadPlane::forward_throttle_pct() { // handle special case where forward thrust motor is used instead of forward pitch. - // but not in autotune as it will upset the results -#if QAUTOTUNE_ENABLED - if (is_positive(q_fwd_thr_gain) && plane.control_mode != &plane.mode_qautotune) { -#else - if (is_positive(q_fwd_thr_gain)) { -#endif - // handle special case where we are using forward throttle instead of forward tilt in Q modes + if (get_vfwd_method() == ActiveFwdThr::NEW) { return 100.0f * q_fwd_throttle; } diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index b033c46dbf..8f5c37f5d5 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -288,7 +288,7 @@ void Tiltrotor::continuous_update(void) #endif if (!quadplane.assisted_flight && - is_positive(plane.quadplane.q_fwd_thr_gain) && + quadplane.get_vfwd_method() == QuadPlane::ActiveFwdThr::NEW && quadplane.is_flying_vtol()) { // We are using the rotor tilt functionality controlled by Q_FWD_THR_GAIN which can