Skip to content

Commit

Permalink
AP_TECS: Converted parameter TKOFF_MODE to TKOFF_OPTIONS
Browse files Browse the repository at this point in the history
  • Loading branch information
Georacer committed Jul 25, 2024
1 parent 7c95fac commit fa03001
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 2 deletions.
3 changes: 2 additions & 1 deletion libraries/AP_TECS/AP_TECS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1458,7 +1458,8 @@ void AP_TECS::_update_throttle_limits() {

// 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;
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 ) {
_THRminf = MIN(_THRminf, aparm.takeoff_throttle_min * 0.01f);
}
Expand Down
7 changes: 6 additions & 1 deletion libraries/AP_Vehicle/AP_FixedWing.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ struct AP_FixedWing {
AP_Int8 throttle_cruise;
AP_Int8 takeoff_throttle_max;
AP_Int8 takeoff_throttle_min;
AP_Int8 takeoff_mode;
AP_Int32 takeoff_options;
AP_Int16 airspeed_min;
AP_Int16 airspeed_max;
AP_Float airspeed_cruise;
Expand Down Expand Up @@ -50,4 +50,9 @@ struct AP_FixedWing {
LAND = 4,
ABORT_LANDING = 7
};

// Bitfields of TKOFF_OPTIONS
enum class TakeoffOption {
THROTTLE_RANGE = (1U << 0), // Unset: Max throttle. Set: Throttle range.
};
};

0 comments on commit fa03001

Please sign in to comment.