mirror of https://github.com/ArduPilot/ardupilot
Plane: Converted paramter TKOFF_MODE into TKOFF_OPTIONS
This commit is contained in:
parent
773c91cec1
commit
c213ee2ef8
|
@ -151,19 +151,19 @@ const AP_Param::Info Plane::var_info[] = {
|
||||||
|
|
||||||
// @Param: TKOFF_THR_MIN
|
// @Param: TKOFF_THR_MIN
|
||||||
// @DisplayName: Takeoff minimum throttle
|
// @DisplayName: Takeoff minimum throttle
|
||||||
// @Description: The minimum throttle to use in takeoffs in AUTO and TAKEOFF flight modes, when TKOFF_MODE=1. Also, the minimum throttle to use in a quadpane forward transition. This can be useful to ensure faster takeoffs or transitions on aircraft where the normal throttle control leads to a slow takeoff or transition. It is used when it is larger than THR_MIN, otherwise THR_MIN is used instead.
|
// @Description: The minimum throttle to use in takeoffs in AUTO and TAKEOFF flight modes, when TKOFF_OPTIONS bit 0 is set. Also, the minimum throttle to use in a quadpane forward transition. This can be useful to ensure faster takeoffs or transitions on aircraft where the normal throttle control leads to a slow takeoff or transition. It is used when it is larger than THR_MIN, otherwise THR_MIN is used instead.
|
||||||
// @Units: %
|
// @Units: %
|
||||||
// @Range: 0 100
|
// @Range: 0 100
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 60),
|
ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 60),
|
||||||
|
|
||||||
// @Param: TKOFF_MODE
|
// @Param: TKOFF_OPTIONS
|
||||||
// @DisplayName: Takeoff mode
|
// @DisplayName: Takeoff options
|
||||||
// @Description: This selects the mode of the takeoff in AUTO and TAKEOFF flight modes. 0: During the takeoff, the maximum allowed throttle is always used (THR_MAX or TKOFF_THR_MAX). 1: During the takeoff TECS is allowed to operate between a minimum (THR_MIN or TKOFF_THR_MIN) and a maximum (THR_MAX or TKOFF_THR_MAX) limit. Applicable only when using an airspeed sensor.
|
// @Description: This selects the mode of the takeoff in AUTO and TAKEOFF flight modes.
|
||||||
// @Values: 0:Traditional,1:Throttle range
|
// @Bitmask: 0: When unset the maximum allowed throttle is always used (THR_MAX or TKOFF_THR_MAX) during takeoff. When set TECS is allowed to operate between a minimum (THR_MIN or TKOFF_THR_MIN) and a maximum (THR_MAX or TKOFF_THR_MAX) limit. Applicable only when using an airspeed sensor.
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
ASCALAR(takeoff_mode, "TKOFF_MODE", 0),
|
ASCALAR(takeoff_options, "TKOFF_OPTIONS", 0),
|
||||||
|
|
||||||
// @Param: TKOFF_TDRAG_ELEV
|
// @Param: TKOFF_TDRAG_ELEV
|
||||||
// @DisplayName: Takeoff tail dragger elevator
|
// @DisplayName: Takeoff tail dragger elevator
|
||||||
|
|
|
@ -358,7 +358,7 @@ public:
|
||||||
k_param_takeoff_throttle_max_t,
|
k_param_takeoff_throttle_max_t,
|
||||||
k_param_autotune_options,
|
k_param_autotune_options,
|
||||||
k_param_takeoff_throttle_min,
|
k_param_takeoff_throttle_min,
|
||||||
k_param_takeoff_mode,
|
k_param_takeoff_options,
|
||||||
};
|
};
|
||||||
|
|
||||||
AP_Int16 format_version;
|
AP_Int16 format_version;
|
||||||
|
|
|
@ -536,10 +536,11 @@ float Plane::apply_throttle_limits(float throttle_in)
|
||||||
}
|
}
|
||||||
// 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.
|
||||||
if (aparm.takeoff_mode.get() == 0 || !ahrs.using_airspeed_sensor()) {
|
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.
|
// 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());
|
min_throttle = MAX(min_throttle, aparm.takeoff_throttle_max.get());
|
||||||
} else if (aparm.takeoff_mode.get() == 1) { // 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());
|
||||||
}
|
}
|
||||||
|
|
|
@ -230,7 +230,8 @@ void Plane::takeoff_calc_throttle(const bool use_max_throttle) {
|
||||||
}
|
}
|
||||||
|
|
||||||
// Set the minimum throttle limit.
|
// Set the minimum throttle limit.
|
||||||
if (aparm.takeoff_mode==0 || !ahrs.using_airspeed_sensor() || use_max_throttle) { // Traditional takeoff 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);
|
TECS_controller.set_throttle_min(0.01f*aparm.takeoff_throttle_max);
|
||||||
} 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.
|
||||||
|
|
Loading…
Reference in New Issue