From 232b6dcef1aa5cd4c8c5b0733fdda006757cd585 Mon Sep 17 00:00:00 2001 From: George Zogopoulos Date: Fri, 4 Oct 2024 19:26:17 +0200 Subject: [PATCH 1/2] autotest: Added back-transition throttle test --- Tools/autotest/quadplane.py | 28 ++++++++++++++++++++++++++++ 1 file changed, 28 insertions(+) diff --git a/Tools/autotest/quadplane.py b/Tools/autotest/quadplane.py index a5a61fe763f79..112ac78f00499 100644 --- a/Tools/autotest/quadplane.py +++ b/Tools/autotest/quadplane.py @@ -1644,6 +1644,33 @@ def TransitionMinThrottle(self): self.fly_home_land_and_disarm() + def BackTransitionMinThrottle(self): + '''Ensure min throttle is applied during back transition.''' + wps = self.create_simple_relhome_mission([ + (mavutil.mavlink.MAV_CMD_NAV_TAKEOFF, 0, 0, 30), + (mavutil.mavlink.MAV_CMD_NAV_WAYPOINT, 2000, 0, 30), + (mavutil.mavlink.MAV_CMD_NAV_RETURN_TO_LAUNCH, 0, 0, 0), + ]) + self.check_mission_upload_download(wps) + self.set_parameter('Q_RTL_MODE', 1) + + trim_pwm = 1000 + 10*self.get_parameter("TRIM_THROTTLE") + min_pwm = 1000 + 10*self.get_parameter("THR_MIN") + + self.change_mode('AUTO') + self.wait_ready_to_arm() + + self.arm_vehicle() + self.context_collect('STATUSTEXT') + + self.wait_statustext("VTOL airbrake", check_context=True, timeout=300) + self.wait_servo_channel_value(3, trim_pwm, comparator=operator.le, timeout=1) + + self.wait_statustext("VTOL position1", check_context=True, timeout=10) + self.wait_servo_channel_value(3, min_pwm+10, comparator=operator.le, timeout=1) + + self.wait_disarmed(timeout=60) + def MAV_CMD_NAV_TAKEOFF(self): '''test issuing takeoff command via mavlink''' self.change_mode('GUIDED') @@ -1901,6 +1928,7 @@ def tests(self): self.mission_MAV_CMD_DO_VTOL_TRANSITION, self.mavlink_MAV_CMD_DO_VTOL_TRANSITION, self.TransitionMinThrottle, + self.BackTransitionMinThrottle, self.MAV_CMD_NAV_TAKEOFF, self.Q_GUIDED_MODE, self.DCMClimbRate, From acd81b57ec91954da712b6256ffd83934cfe9c38 Mon Sep 17 00:00:00 2001 From: George Zogopoulos Date: Mon, 7 Oct 2024 11:08:29 +0200 Subject: [PATCH 2/2] Plane: Fix SLT_Transition::active_frwd() check --- ArduPlane/quadplane.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index a3e4c39e2ef3c..eb6a16b47c76c 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -4374,7 +4374,9 @@ bool SLT_Transition::allow_update_throttle_mix() const bool SLT_Transition::active_frwd() const { - return quadplane.assisted_flight && ((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER)); + return quadplane.assisted_flight && // We need to be in assisted flight... + ((transition_state == TRANSITION_AIRSPEED_WAIT) || (transition_state == TRANSITION_TIMER)) // ... and a transition must be active... + && !quadplane.in_vtol_airbrake(); // ... but not executing an QPOS_AIRBRAKE maneuver during an automated landing. } /*