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

Fix for unhandled TKOFF_THR_MAX #27693

Merged
merged 3 commits into from
Jul 31, 2024
Merged
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
19 changes: 15 additions & 4 deletions ArduPlane/servos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -521,12 +521,10 @@ float Plane::apply_throttle_limits(float throttle_in)

// Query the conditions where TKOFF_THR_MAX applies.
const bool use_takeoff_throttle =
#if HAL_QUADPLANE_ENABLED
quadplane.in_transition() ||
#endif
(flight_stage == AP_FixedWing::FlightStage::TAKEOFF) ||
(flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING);

// Handle throttle limits for takeoff conditions.
if (use_takeoff_throttle) {
if (aparm.takeoff_throttle_max != 0) {
// Replace max throttle with the takeoff max throttle setting.
Expand All @@ -539,7 +537,11 @@ float Plane::apply_throttle_limits(float throttle_in)
const bool use_throttle_range = (aparm.takeoff_options & (uint32_t)AP_FixedWing::TakeoffOption::THROTTLE_RANGE);
if (!use_throttle_range || !ahrs.using_airspeed_sensor()) {
// Use a constant max throttle throughout the takeoff or when airspeed readings are not available.
min_throttle = MAX(min_throttle, aparm.takeoff_throttle_max.get());
if (aparm.takeoff_throttle_max.get() == 0) {
min_throttle = MAX(min_throttle, aparm.throttle_max.get());
} else {
min_throttle = MAX(min_throttle, aparm.takeoff_throttle_max.get());
}
} else if (use_throttle_range) { // Use a throttle range through the takeoff.
if (aparm.takeoff_throttle_min.get() != 0) { // This is enabled by TKOFF_MODE==1.
min_throttle = MAX(min_throttle, aparm.takeoff_throttle_min.get());
Expand All @@ -551,6 +553,15 @@ float Plane::apply_throttle_limits(float throttle_in)
min_throttle = 0;
}

// Handle throttle limits for transition conditions.
#if HAL_QUADPLANE_ENABLED
if (quadplane.in_transition()) {
tridge marked this conversation as resolved.
Show resolved Hide resolved
if (aparm.takeoff_throttle_max != 0) {
max_throttle = aparm.takeoff_throttle_max.get();
}
}
#endif

// Compensate the limits for battery voltage drop.
// This relaxes the limits when the battery is getting depleted.
g2.fwd_batt_cmp.apply_min_max(min_throttle, max_throttle);
Expand Down
3 changes: 2 additions & 1 deletion ArduPlane/takeoff.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -232,7 +232,8 @@ void Plane::takeoff_calc_throttle(const bool use_max_throttle) {
// Set the minimum throttle limit.
const bool use_throttle_range = (aparm.takeoff_options & (uint32_t)AP_FixedWing::TakeoffOption::THROTTLE_RANGE);
if (!use_throttle_range || !ahrs.using_airspeed_sensor() || use_max_throttle) { // Traditional takeoff throttle limit.
TECS_controller.set_throttle_min(0.01f*aparm.takeoff_throttle_max);
float min_throttle = (aparm.takeoff_throttle_max != 0) ? 0.01f*aparm.takeoff_throttle_max : 0.01f*aparm.throttle_max;
TECS_controller.set_throttle_min(min_throttle);
} else { // TKOFF_MODE == 1, allow for a throttle range.
if (aparm.takeoff_throttle_min != 0) { // Override THR_MIN.
TECS_controller.set_throttle_min(0.01f*aparm.takeoff_throttle_min);
Expand Down
41 changes: 41 additions & 0 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -4714,6 +4714,46 @@ def TakeoffTakeoff3(self):

self.fly_home_land_and_disarm()

def TakeoffTakeoff4(self):
'''Test the behaviour of a takeoff in TAKEOFF mode, pt4.

This is the same as case #3, but with almost stock parameters and without a catapult.

Conditions:
- ARSPD_USE=0
'''

self.customise_SITL_commandline(
[],
model='plane-catapult',
defaults_filepath=self.model_defaults_filepath("plane")
)
self.set_parameters({
"ARSPD_USE": 0.0,
})
self.change_mode("TAKEOFF")

self.wait_ready_to_arm()
self.arm_vehicle()

# Check whether we're at max throttle below TKOFF_LVL_ALT.
test_alt = self.get_parameter("TKOFF_LVL_ALT")-10
self.wait_altitude(test_alt, test_alt+2, relative=True)
self.assert_servo_channel_value(3, 1000+10*(self.get_parameter("THR_MAX")), operator.le)
self.assert_servo_channel_value(3, 1000+10*(self.get_parameter("THR_MAX"))-10, operator.ge)

# Check whether we're still at max throttle past TKOFF_LVL_ALT.
test_alt = self.get_parameter("TKOFF_LVL_ALT")+10
self.wait_altitude(test_alt, test_alt+2, relative=True)
self.assert_servo_channel_value(3, 1000+10*(self.get_parameter("THR_MAX")), operator.le)
self.assert_servo_channel_value(3, 1000+10*(self.get_parameter("THR_MAX"))-10, operator.ge)

# Wait for the takeoff to complete.
target_alt = self.get_parameter("TKOFF_ALT")
self.wait_altitude(target_alt-5, target_alt, relative=True)

self.fly_home_land_and_disarm()

def DCMFallback(self):
'''Really annoy the EKF and force fallback'''
self.reboot_sitl()
Expand Down Expand Up @@ -6062,6 +6102,7 @@ def tests(self):
self.TakeoffTakeoff1,
self.TakeoffTakeoff2,
self.TakeoffTakeoff3,
self.TakeoffTakeoff4,
self.ForcedDCM,
self.DCMFallback,
self.MAVFTP,
Expand Down
Loading