AP_TECS: Converted parameter TKOFF_MODE to TKOFF_OPTIONS

This commit is contained in:
George Zogopoulos 2024-07-25 21:29:22 +02:00 committed by Andrew Tridgell
parent c213ee2ef8
commit e227187e72
2 changed files with 8 additions and 2 deletions

View File

@ -1462,7 +1462,8 @@ void AP_TECS::_update_throttle_limits() {
// If less min throttle is allowed during takeoff, use it. // If less min throttle is allowed during takeoff, use it.
bool use_takeoff_throttle = _flight_stage == AP_FixedWing::FlightStage::TAKEOFF || _flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING; bool use_takeoff_throttle = _flight_stage == AP_FixedWing::FlightStage::TAKEOFF || _flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING;
use_takeoff_throttle = use_takeoff_throttle && (aparm.takeoff_mode == 1) && (aparm.takeoff_throttle_min != 0); const bool use_throttle_range = (aparm.takeoff_options & (uint32_t)AP_FixedWing::TakeoffOption::THROTTLE_RANGE);
use_takeoff_throttle = use_takeoff_throttle && (use_throttle_range == 1) && (aparm.takeoff_throttle_min != 0);
if ( use_takeoff_throttle ) { if ( use_takeoff_throttle ) {
_THRminf = MIN(_THRminf, aparm.takeoff_throttle_min * 0.01f); _THRminf = MIN(_THRminf, aparm.takeoff_throttle_min * 0.01f);
} }

View File

@ -12,7 +12,7 @@ struct AP_FixedWing {
AP_Int8 throttle_cruise; AP_Int8 throttle_cruise;
AP_Int8 takeoff_throttle_max; AP_Int8 takeoff_throttle_max;
AP_Int8 takeoff_throttle_min; AP_Int8 takeoff_throttle_min;
AP_Int8 takeoff_mode; AP_Int32 takeoff_options;
AP_Int16 airspeed_min; AP_Int16 airspeed_min;
AP_Int16 airspeed_max; AP_Int16 airspeed_max;
AP_Float airspeed_cruise; AP_Float airspeed_cruise;
@ -51,4 +51,9 @@ struct AP_FixedWing {
LAND = 4, LAND = 4,
ABORT_LANDING = 7 ABORT_LANDING = 7
}; };
// Bitfields of TKOFF_OPTIONS
enum class TakeoffOption {
THROTTLE_RANGE = (1U << 0), // Unset: Max throttle. Set: Throttle range.
};
}; };