Skip to content

Commit

Permalink
Move _TAScruise declaration to header
Browse files Browse the repository at this point in the history
  • Loading branch information
Cole Perschon committed Oct 31, 2023
1 parent bd9087e commit 0f5e800
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 1 deletion.
4 changes: 3 additions & 1 deletion libraries/AP_TECS/AP_TECS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -470,11 +470,13 @@ void AP_TECS::_update_speed_demand(void)
// Constrain speed demand, taking into account the load factor
_TAS_dem = constrain_float(_TAS_dem, _TASmin, _TASmax);

// Determine the true cruising airspeed (m/s)
_TAScruise = 0.01f * (float)aparm.airspeed_cruise_cm * _ahrs.get_EAS2TAS();

// calculate velocity rate limits based on physical performance limits
// provision to use a different rate limit if bad descent or underspeed condition exists
// Use 50% of maximum energy rate on gain, 90% on dissipation to allow margin for total energy controller
const float velRateMax = 0.5f * _STEdot_max / _TAS_state;
const float _TAScruise = 0.01f * (float)aparm.airspeed_cruise_cm * _ahrs.get_EAS2TAS();
// Maximum permissible rate of deceleration value at max airspeed
const float velRateNegMax = 0.9f * _STEdot_neg_max / _TASmax;
// Maximum permissible rate of deceleration value at cruise speed
Expand Down
3 changes: 3 additions & 0 deletions libraries/AP_TECS/AP_TECS.h
Original file line number Diff line number Diff line change
Expand Up @@ -266,6 +266,9 @@ class AP_TECS {
float _TASmax;
float _TASmin;

// True cruising airspeed (TRIM_ARSPD)
float _TAScruise;

// Current true airspeed demand
float _TAS_dem;

Expand Down

0 comments on commit 0f5e800

Please sign in to comment.