Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: Do not apply minimum throttle during SLT VTOL airbrake #28329

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 3 additions & 1 deletion ArduPlane/quadplane.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
}

/*
Expand Down
28 changes: 28 additions & 0 deletions Tools/autotest/quadplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -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')
Expand Down Expand Up @@ -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,
Expand Down
Loading