mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: Fixed unhandled TKOFF_THR_MAX=0 case
This commit is contained in:
parent
21ad679b61
commit
ae6f41f414
@ -534,12 +534,17 @@ float Plane::apply_throttle_limits(float throttle_in)
|
|||||||
// Or (in contrast) to give some extra throttle during the initial climb.
|
// Or (in contrast) to give some extra throttle during the initial climb.
|
||||||
max_throttle = aparm.takeoff_throttle_max.get();
|
max_throttle = aparm.takeoff_throttle_max.get();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Do not allow min throttle to go below a lower threshold.
|
// Do not allow min throttle to go below a lower threshold.
|
||||||
// This is typically done to protect against premature stalls close to the ground.
|
// This is typically done to protect against premature stalls close to the ground.
|
||||||
const bool use_throttle_range = (aparm.takeoff_options & (uint32_t)AP_FixedWing::TakeoffOption::THROTTLE_RANGE);
|
const bool use_throttle_range = (aparm.takeoff_options & (uint32_t)AP_FixedWing::TakeoffOption::THROTTLE_RANGE);
|
||||||
if (!use_throttle_range || !ahrs.using_airspeed_sensor()) {
|
if (!use_throttle_range || !ahrs.using_airspeed_sensor()) {
|
||||||
// Use a constant max throttle throughout the takeoff or when airspeed readings are not available.
|
// 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.
|
} 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.
|
if (aparm.takeoff_throttle_min.get() != 0) { // This is enabled by TKOFF_MODE==1.
|
||||||
min_throttle = MAX(min_throttle, aparm.takeoff_throttle_min.get());
|
min_throttle = MAX(min_throttle, aparm.takeoff_throttle_min.get());
|
||||||
|
@ -232,7 +232,8 @@ void Plane::takeoff_calc_throttle(const bool use_max_throttle) {
|
|||||||
// Set the minimum throttle limit.
|
// Set the minimum throttle limit.
|
||||||
const bool use_throttle_range = (aparm.takeoff_options & (uint32_t)AP_FixedWing::TakeoffOption::THROTTLE_RANGE);
|
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.
|
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.
|
} else { // TKOFF_MODE == 1, allow for a throttle range.
|
||||||
if (aparm.takeoff_throttle_min != 0) { // Override THR_MIN.
|
if (aparm.takeoff_throttle_min != 0) { // Override THR_MIN.
|
||||||
TECS_controller.set_throttle_min(0.01f*aparm.takeoff_throttle_min);
|
TECS_controller.set_throttle_min(0.01f*aparm.takeoff_throttle_min);
|
||||||
|
Loading…
Reference in New Issue
Block a user