PX4 Firmware
PX4 Autopilot Software http://px4.io
TECS Class Reference

#include <tecs.h>

Collaboration diagram for TECS:

Public Types

enum  ECL_TECS_MODE { ECL_TECS_MODE_NORMAL = 0, ECL_TECS_MODE_UNDERSPEED, ECL_TECS_MODE_BAD_DESCENT, ECL_TECS_MODE_CLIMBOUT }
 

Public Member Functions

 TECS ()=default
 
 ~TECS ()=default
 
 TECS (const TECS &)=delete
 
TECSoperator= (const TECS &)=delete
 
 TECS (TECS &&)=delete
 
TECSoperator= (TECS &&)=delete
 
bool airspeed_sensor_enabled ()
 Get the current airspeed status. More...
 
void enable_airspeed (bool enabled)
 Set the airspeed enable state. More...
 
void update_vehicle_state_estimates (float airspeed, const matrix::Dcmf &rotMat, const matrix::Vector3f &accel_body, bool altitude_lock, bool in_air, float altitude, bool vz_valid, float vz, float az)
 Updates the following vehicle kineamtic state estimates: Vertical position, velocity and acceleration. More...
 
void update_pitch_throttle (const matrix::Dcmf &rotMat, float pitch, float baro_altitude, float hgt_setpoint, float EAS_setpoint, float indicated_airspeed, float eas_to_tas, bool climb_out_setpoint, float pitch_min_climbout, float throttle_min, float throttle_setpoint_max, float throttle_cruise, float pitch_limit_min, float pitch_limit_max)
 Update the control loop calculations. More...
 
float get_throttle_setpoint (void)
 
float get_pitch_setpoint ()
 
float get_speed_weight ()
 
void reset_state ()
 
void set_detect_underspeed_enabled (bool enabled)
 
void set_time_const (float time_const)
 
void set_integrator_gain (float gain)
 
void set_min_sink_rate (float rate)
 
void set_max_sink_rate (float sink_rate)
 
void set_max_climb_rate (float climb_rate)
 
void set_height_comp_filter_omega (float omega)
 
void set_heightrate_ff (float heightrate_ff)
 
void set_heightrate_p (float heightrate_p)
 
void set_indicated_airspeed_max (float airspeed)
 
void set_indicated_airspeed_min (float airspeed)
 
void set_pitch_damping (float damping)
 
void set_vertical_accel_limit (float limit)
 
void set_speed_comp_filter_omega (float omega)
 
void set_speed_weight (float weight)
 
void set_speedrate_p (float speedrate_p)
 
void set_time_const_throt (float time_const_throt)
 
void set_throttle_damp (float throttle_damp)
 
void set_throttle_slewrate (float slewrate)
 
void set_roll_throttle_compensation (float compensation)
 
uint64_t timestamp ()
 
ECL_TECS_MODE tecs_mode ()
 
float hgt_setpoint_adj ()
 
float vert_pos_state ()
 
float TAS_setpoint_adj ()
 
float tas_state ()
 
float hgt_rate_setpoint ()
 
float vert_vel_state ()
 
float TAS_rate_setpoint ()
 
float speed_derivative ()
 
float STE_error ()
 
float STE_rate_error ()
 
float SEB_error ()
 
float SEB_rate_error ()
 
float throttle_integ_state ()
 
float pitch_integ_state ()
 
void handle_alt_step (float delta_alt, float altitude)
 Handle the altitude reset. More...
 

Private Member Functions

void _update_speed_states (float airspeed_setpoint, float indicated_airspeed, float eas_to_tas)
 Update the airspeed internal state using a second order complementary filter. More...
 
void _update_speed_setpoint ()
 Update the desired airspeed. More...
 
void _update_height_setpoint (float desired, float state)
 Update the desired height. More...
 
void _detect_underspeed ()
 Detect if the system is not capable of maintaining airspeed. More...
 
void _update_energy_estimates ()
 Update specific energy. More...
 
void _update_throttle_setpoint (float throttle_cruise, const matrix::Dcmf &rotMat)
 Update throttle setpoint. More...
 
void _detect_uncommanded_descent ()
 Detect an uncommanded descent. More...
 
void _update_pitch_setpoint ()
 Update the pitch setpoint. More...
 
void _initialize_states (float pitch, float throttle_cruise, float baro_altitude, float pitch_min_climbout, float eas_to_tas)
 Initialize the controller. More...
 
void _update_STE_rate_lim ()
 Calculate specific total energy rate limits. More...
 

Private Attributes

uint64_t _state_update_timestamp {0}
 last timestamp of the 50 Hz function call More...
 
uint64_t _speed_update_timestamp {0}
 last timestamp of the speed function call More...
 
uint64_t _pitch_update_timestamp {0}
 last timestamp of the pitch function call More...
 
float _hgt_estimate_freq {0.0f}
 cross-over frequency of the height rate complementary filter (rad/sec) More...
 
float _tas_estimate_freq {0.0f}
 cross-over frequency of the true airspeed complementary filter (rad/sec) More...
 
float _max_climb_rate {2.0f}
 climb rate produced by max allowed throttle (m/sec) More...
 
float _min_sink_rate {1.0f}
 sink rate produced by min allowed throttle (m/sec) More...
 
float _max_sink_rate {2.0f}
 maximum safe sink rate (m/sec) More...
 
float _pitch_time_constant {5.0f}
 control time constant used by the pitch demand calculation (sec) More...
 
float _throttle_time_constant {8.0f}
 control time constant used by the throttle demand calculation (sec) More...
 
float _pitch_damping_gain {0.0f}
 damping gain of the pitch demand calculation (sec) More...
 
float _throttle_damping_gain {0.0f}
 damping gain of the throttle demand calculation (sec) More...
 
float _integrator_gain {0.0f}
 integrator gain used by the throttle and pitch demand calculation More...
 
float _vert_accel_limit {0.0f}
 magnitude of the maximum vertical acceleration allowed (m/sec**2) More...
 
float _load_factor_correction {0.0f}
 gain from normal load factor increase to total energy rate demand (m**2/sec**3) More...
 
float _pitch_speed_weight {1.0f}
 speed control weighting used by pitch demand calculation More...
 
float _height_error_gain {0.0f}
 gain from height error to demanded climb rate (1/sec) More...
 
float _height_setpoint_gain_ff {0.0f}
 gain from height demand derivative to demanded climb rate More...
 
float _speed_error_gain {0.0f}
 gain from speed error to demanded speed rate (1/sec) More...
 
float _indicated_airspeed_min {3.0f}
 equivalent airspeed demand lower limit (m/sec) More...
 
float _indicated_airspeed_max {30.0f}
 equivalent airspeed demand upper limit (m/sec) More...
 
float _throttle_slewrate {0.0f}
 throttle demand slew rate limit (1/sec) More...
 
float _throttle_setpoint {0.0f}
 normalized throttle demand (0..1) More...
 
float _pitch_setpoint {0.0f}
 pitch angle demand (radians) More...
 
float _vert_accel_state {0.0f}
 complimentary filter state - height second derivative (m/sec**2) More...
 
float _vert_vel_state {0.0f}
 complimentary filter state - height rate (m/sec) More...
 
float _vert_pos_state {0.0f}
 complimentary filter state - height (m) More...
 
float _tas_rate_state {0.0f}
 complimentary filter state - true airspeed first derivative (m/sec**2) More...
 
float _tas_state {0.0f}
 complimentary filter state - true airspeed (m/sec) More...
 
float _throttle_integ_state {0.0f}
 throttle integrator state More...
 
float _pitch_integ_state {0.0f}
 pitch integrator state (rad) More...
 
float _last_throttle_setpoint {0.0f}
 throttle demand rate limiter state (1/sec) More...
 
float _last_pitch_setpoint {0.0f}
 pitch demand rate limiter state (rad/sec) More...
 
float _speed_derivative {0.0f}
 rate of change of speed along X axis (m/sec**2) More...
 
float _EAS {0.0f}
 equivalent airspeed (m/sec) More...
 
float _TAS_max {30.0f}
 true airpeed demand upper limit (m/sec) More...
 
float _TAS_min {3.0f}
 true airpeed demand lower limit (m/sec) More...
 
float _TAS_setpoint {0.0f}
 current airpeed demand (m/sec) More...
 
float _TAS_setpoint_last {0.0f}
 previous true airpeed demand (m/sec) More...
 
float _EAS_setpoint {0.0f}
 Equivalent airspeed demand (m/sec) More...
 
float _TAS_setpoint_adj {0.0f}
 true airspeed demand tracked by the TECS algorithm (m/sec) More...
 
float _TAS_rate_setpoint {0.0f}
 true airspeed rate demand tracked by the TECS algorithm (m/sec**2) More...
 
float _hgt_setpoint {0.0f}
 demanded height tracked by the TECS algorithm (m) More...
 
float _hgt_setpoint_in_prev {0.0f}
 previous value of _hgt_setpoint after noise filtering (m) More...
 
float _hgt_setpoint_prev {0.0f}
 previous value of _hgt_setpoint after noise filtering and rate limiting (m) More...
 
float _hgt_setpoint_adj {0.0f}
 demanded height used by the control loops after all filtering has been applied (m) More...
 
float _hgt_setpoint_adj_prev {0.0f}
 value of _hgt_setpoint_adj from previous frame (m) More...
 
float _hgt_rate_setpoint {0.0f}
 demanded climb rate tracked by the TECS algorithm More...
 
float _pitch_setpoint_unc {0.0f}
 pitch demand before limiting (rad) More...
 
float _STE_rate_max {0.0f}
 specific total energy rate upper limit achieved when throttle is at _throttle_setpoint_max (m**2/sec**3) More...
 
float _STE_rate_min {0.0f}
 specific total energy rate lower limit acheived when throttle is at _throttle_setpoint_min (m**2/sec**3) More...
 
float _throttle_setpoint_max {0.0f}
 normalised throttle upper limit More...
 
float _throttle_setpoint_min {0.0f}
 normalised throttle lower limit More...
 
float _pitch_setpoint_max {0.5f}
 pitch demand upper limit (rad) More...
 
float _pitch_setpoint_min {-0.5f}
 pitch demand lower limit (rad) More...
 
float _SPE_setpoint {0.0f}
 specific potential energy demand (m**2/sec**2) More...
 
float _SKE_setpoint {0.0f}
 specific kinetic energy demand (m**2/sec**2) More...
 
float _SPE_rate_setpoint {0.0f}
 specific potential energy rate demand (m**2/sec**3) More...
 
float _SKE_rate_setpoint {0.0f}
 specific kinetic energy rate demand (m**2/sec**3) More...
 
float _SPE_estimate {0.0f}
 specific potential energy estimate (m**2/sec**2) More...
 
float _SKE_estimate {0.0f}
 specific kinetic energy estimate (m**2/sec**2) More...
 
float _SPE_rate {0.0f}
 specific potential energy rate estimate (m**2/sec**3) More...
 
float _SKE_rate {0.0f}
 specific kinetic energy rate estimate (m**2/sec**3) More...
 
float _STE_error {0.0f}
 specific total energy error (m**2/sec**2) More...
 
float _STE_rate_error {0.0f}
 specific total energy rate error (m**2/sec**3) More...
 
float _SEB_error {0.0f}
 specific energy balance error (m**2/sec**2) More...
 
float _SEB_rate_error {0.0f}
 specific energy balance rate error (m**2/sec**3) More...
 
float _dt {DT_DEFAULT}
 Time since last update of main TECS loop (sec) More...
 
bool _underspeed_detected {false}
 true when an underspeed condition has been detected More...
 
bool _detect_underspeed_enabled {true}
 true when underspeed detection is enabled More...
 
bool _uncommanded_descent_recovery {false}
 true when a continuous descent caused by an unachievable airspeed demand has been detected More...
 
bool _climbout_mode_active {false}
 true when in climbout mode More...
 
bool _airspeed_enabled {false}
 true when airspeed use has been enabled More...
 
bool _states_initalized {false}
 true when TECS states have been iniitalized More...
 
bool _in_air {false}
 true when the vehicle is flying More...
 

Static Private Attributes

static constexpr float DT_DEFAULT = 0.02f
 default value for _dt (sec) More...
 

Detailed Description

Definition at line 45 of file tecs.h.

Member Enumeration Documentation

◆ ECL_TECS_MODE

Enumerator
ECL_TECS_MODE_NORMAL 
ECL_TECS_MODE_UNDERSPEED 
ECL_TECS_MODE_BAD_DESCENT 
ECL_TECS_MODE_CLIMBOUT 

Definition at line 94 of file tecs.h.

Constructor & Destructor Documentation

◆ TECS() [1/3]

TECS::TECS ( )
default

◆ ~TECS()

TECS::~TECS ( )
default

◆ TECS() [2/3]

TECS::TECS ( const TECS )
delete

◆ TECS() [3/3]

TECS::TECS ( TECS &&  )
delete

Member Function Documentation

◆ _detect_uncommanded_descent()

void TECS::_detect_uncommanded_descent ( )
private

Detect an uncommanded descent.

Definition at line 399 of file tecs.cpp.

References _SKE_rate, _SPE_rate, _STE_error, _throttle_setpoint, _throttle_setpoint_max, _uncommanded_descent_recovery, _underspeed_detected, and f().

Referenced by update_pitch_throttle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _detect_underspeed()

void TECS::_detect_underspeed ( )
private

Detect if the system is not capable of maintaining airspeed.

Definition at line 268 of file tecs.cpp.

References _detect_underspeed_enabled, _hgt_setpoint_adj, _TAS_min, _tas_state, _throttle_setpoint, _throttle_setpoint_max, _underspeed_detected, _vert_pos_state, and f().

Referenced by update_pitch_throttle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _initialize_states()

void TECS::_initialize_states ( float  pitch,
float  throttle_cruise,
float  baro_altitude,
float  pitch_min_climbout,
float  eas_to_tas 
)
private

Initialize the controller.

Definition at line 518 of file tecs.cpp.

References _climbout_mode_active, _dt, _EAS, _hgt_setpoint_adj, _hgt_setpoint_adj_prev, _hgt_setpoint_in_prev, _hgt_setpoint_prev, _in_air, _last_pitch_setpoint, _last_throttle_setpoint, _pitch_integ_state, _pitch_setpoint_max, _pitch_setpoint_min, _pitch_setpoint_unc, _pitch_update_timestamp, _states_initalized, _STE_rate_error, _tas_rate_state, _TAS_setpoint_adj, _TAS_setpoint_last, _tas_state, _throttle_integ_state, _throttle_setpoint_max, _throttle_setpoint_min, _uncommanded_descent_recovery, _underspeed_detected, _vert_accel_state, _vert_pos_state, _vert_vel_state, math::constrain(), DT_DEFAULT, DT_MAX, and DT_MIN.

Referenced by update_pitch_throttle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _update_energy_estimates()

void TECS::_update_energy_estimates ( )
private

Update specific energy.

Definition at line 285 of file tecs.cpp.

References _hgt_rate_setpoint, _hgt_setpoint_adj, _SKE_estimate, _SKE_rate, _SKE_rate_setpoint, _SKE_setpoint, _SPE_estimate, _SPE_rate, _SPE_rate_setpoint, _SPE_setpoint, _speed_derivative, _TAS_rate_setpoint, _TAS_setpoint_adj, _tas_state, _vert_pos_state, _vert_vel_state, and CONSTANTS_ONE_G.

Referenced by update_pitch_throttle().

Here is the caller graph for this function:

◆ _update_height_setpoint()

void TECS::_update_height_setpoint ( float  desired,
float  state 
)
private

Update the desired height.

Definition at line 222 of file tecs.cpp.

References _dt, _height_error_gain, _height_setpoint_gain_ff, _hgt_rate_setpoint, _hgt_setpoint, _hgt_setpoint_adj, _hgt_setpoint_adj_prev, _hgt_setpoint_in_prev, _hgt_setpoint_prev, _max_climb_rate, _max_sink_rate, f(), ISFINITE, and state.

Referenced by update_pitch_throttle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _update_pitch_setpoint()

void TECS::_update_pitch_setpoint ( )
private

Update the pitch setpoint.

Definition at line 426 of file tecs.cpp.

References _climbout_mode_active, _dt, _integrator_gain, _last_pitch_setpoint, _pitch_damping_gain, _pitch_integ_state, _pitch_setpoint, _pitch_setpoint_max, _pitch_setpoint_min, _pitch_setpoint_unc, _pitch_speed_weight, _pitch_time_constant, _SEB_error, _SEB_rate_error, _SKE_estimate, _SKE_rate, _SKE_rate_setpoint, _SKE_setpoint, _SPE_estimate, _SPE_rate, _SPE_rate_setpoint, _SPE_setpoint, _tas_state, _underspeed_detected, _vert_accel_limit, airspeed_sensor_enabled(), CONSTANTS_ONE_G, math::constrain(), f(), math::max(), and math::min().

Referenced by update_pitch_throttle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _update_speed_setpoint()

void TECS::_update_speed_setpoint ( )
private

Update the desired airspeed.

Definition at line 199 of file tecs.cpp.

References _speed_error_gain, _STE_rate_max, _STE_rate_min, _TAS_max, _TAS_min, _TAS_rate_setpoint, _TAS_setpoint, _TAS_setpoint_adj, _tas_state, _uncommanded_descent_recovery, _underspeed_detected, and math::constrain().

Referenced by update_pitch_throttle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _update_speed_states()

void TECS::_update_speed_states ( float  airspeed_setpoint,
float  indicated_airspeed,
float  eas_to_tas 
)
private

Update the airspeed internal state using a second order complementary filter.

Definition at line 149 of file tecs.cpp.

References _EAS, _EAS_setpoint, _in_air, _indicated_airspeed_max, _indicated_airspeed_min, _speed_derivative, _speed_update_timestamp, _tas_estimate_freq, _TAS_max, _TAS_min, _tas_rate_state, _TAS_setpoint, _tas_state, airspeed_sensor_enabled(), math::constrain(), dt, DT_MAX, DT_MIN, ecl_absolute_time, f(), ISFINITE, and math::max().

Referenced by update_pitch_throttle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ _update_STE_rate_lim()

void TECS::_update_STE_rate_lim ( )
private

Calculate specific total energy rate limits.

Definition at line 573 of file tecs.cpp.

References _max_climb_rate, _min_sink_rate, _STE_rate_max, _STE_rate_min, and CONSTANTS_ONE_G.

Referenced by update_pitch_throttle().

Here is the caller graph for this function:

◆ _update_throttle_setpoint()

void TECS::_update_throttle_setpoint ( float  throttle_cruise,
const matrix::Dcmf rotMat 
)
private

Update throttle setpoint.

Definition at line 304 of file tecs.cpp.

References _climbout_mode_active, _dt, _integrator_gain, _last_throttle_setpoint, _load_factor_correction, _SKE_estimate, _SKE_rate, _SKE_rate_setpoint, _SKE_setpoint, _SPE_estimate, _SPE_rate, _SPE_rate_setpoint, _SPE_setpoint, _STE_error, _STE_rate_error, _STE_rate_max, _STE_rate_min, _throttle_damping_gain, _throttle_integ_state, _throttle_setpoint, _throttle_setpoint_max, _throttle_setpoint_min, _throttle_slewrate, _throttle_time_constant, _underspeed_detected, airspeed_sensor_enabled(), math::constrain(), and f().

Referenced by update_pitch_throttle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ airspeed_sensor_enabled()

bool TECS::airspeed_sensor_enabled ( )
inline

Get the current airspeed status.

Returns
true if airspeed is enabled for control

Definition at line 62 of file tecs.h.

References _airspeed_enabled.

Referenced by _update_pitch_setpoint(), _update_speed_states(), _update_throttle_setpoint(), and update_vehicle_state_estimates().

Here is the caller graph for this function:

◆ enable_airspeed()

void TECS::enable_airspeed ( bool  enabled)
inline

Set the airspeed enable state.

Definition at line 67 of file tecs.h.

References _airspeed_enabled, update_pitch_throttle(), and update_vehicle_state_estimates().

Referenced by FixedwingPositionControl::airspeed_poll().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_pitch_setpoint()

float TECS::get_pitch_setpoint ( )
inline

Definition at line 89 of file tecs.h.

References _pitch_setpoint.

Referenced by FixedwingPositionControl::get_tecs_pitch().

Here is the caller graph for this function:

◆ get_speed_weight()

float TECS::get_speed_weight ( )
inline

Definition at line 90 of file tecs.h.

References _pitch_speed_weight.

◆ get_throttle_setpoint()

float TECS::get_throttle_setpoint ( void  )
inline

Definition at line 88 of file tecs.h.

References _throttle_setpoint.

Referenced by FixedwingPositionControl::get_tecs_thrust().

Here is the caller graph for this function:

◆ handle_alt_step()

void TECS::handle_alt_step ( float  delta_alt,
float  altitude 
)
inline

Handle the altitude reset.

If the estimation system resets the height in one discrete step this will gracefully even out the reset over time.

Definition at line 162 of file tecs.h.

References _hgt_setpoint_adj_prev, _hgt_setpoint_in_prev, _hgt_setpoint_prev, _vert_accel_state, _vert_pos_state, _vert_vel_state, and ECL_TECS_MODE_NORMAL.

Referenced by FixedwingPositionControl::Run().

Here is the caller graph for this function:

◆ hgt_rate_setpoint()

float TECS::hgt_rate_setpoint ( )
inline

Definition at line 141 of file tecs.h.

References _hgt_rate_setpoint.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ hgt_setpoint_adj()

float TECS::hgt_setpoint_adj ( )
inline

Definition at line 135 of file tecs.h.

References _hgt_setpoint_adj.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ operator=() [1/2]

TECS& TECS::operator= ( const TECS )
delete

◆ operator=() [2/2]

TECS& TECS::operator= ( TECS &&  )
delete

◆ pitch_integ_state()

float TECS::pitch_integ_state ( )
inline

Definition at line 154 of file tecs.h.

References _pitch_integ_state.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ reset_state()

void TECS::reset_state ( )
inline

Definition at line 92 of file tecs.h.

References _states_initalized.

Referenced by FixedwingPositionControl::control_position(), and FixedwingPositionControl::tecs_update_pitch_throttle().

Here is the caller graph for this function:

◆ SEB_error()

float TECS::SEB_error ( )
inline

Definition at line 150 of file tecs.h.

References _SEB_error.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ SEB_rate_error()

float TECS::SEB_rate_error ( )
inline

Definition at line 151 of file tecs.h.

References _SEB_rate_error.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ set_detect_underspeed_enabled()

void TECS::set_detect_underspeed_enabled ( bool  enabled)
inline

Definition at line 101 of file tecs.h.

References _detect_underspeed_enabled.

Referenced by FixedwingPositionControl::tecs_update_pitch_throttle().

Here is the caller graph for this function:

◆ set_height_comp_filter_omega()

void TECS::set_height_comp_filter_omega ( float  omega)
inline

Definition at line 111 of file tecs.h.

References _hgt_estimate_freq.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_heightrate_ff()

void TECS::set_heightrate_ff ( float  heightrate_ff)
inline

Definition at line 112 of file tecs.h.

References _height_setpoint_gain_ff.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_heightrate_p()

void TECS::set_heightrate_p ( float  heightrate_p)
inline

Definition at line 113 of file tecs.h.

References _height_error_gain.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_indicated_airspeed_max()

void TECS::set_indicated_airspeed_max ( float  airspeed)
inline

Definition at line 115 of file tecs.h.

References _indicated_airspeed_max.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_indicated_airspeed_min()

void TECS::set_indicated_airspeed_min ( float  airspeed)
inline

Definition at line 116 of file tecs.h.

References _indicated_airspeed_min.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_integrator_gain()

void TECS::set_integrator_gain ( float  gain)
inline

Definition at line 105 of file tecs.h.

References _integrator_gain.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_max_climb_rate()

void TECS::set_max_climb_rate ( float  climb_rate)
inline

Definition at line 109 of file tecs.h.

References _max_climb_rate.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_max_sink_rate()

void TECS::set_max_sink_rate ( float  sink_rate)
inline

Definition at line 108 of file tecs.h.

References _max_sink_rate.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_min_sink_rate()

void TECS::set_min_sink_rate ( float  rate)
inline

Definition at line 107 of file tecs.h.

References _min_sink_rate.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_pitch_damping()

void TECS::set_pitch_damping ( float  damping)
inline

Definition at line 118 of file tecs.h.

References _pitch_damping_gain.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_roll_throttle_compensation()

void TECS::set_roll_throttle_compensation ( float  compensation)
inline

Definition at line 129 of file tecs.h.

References _load_factor_correction.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_speed_comp_filter_omega()

void TECS::set_speed_comp_filter_omega ( float  omega)
inline

Definition at line 121 of file tecs.h.

References _tas_estimate_freq.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_speed_weight()

void TECS::set_speed_weight ( float  weight)
inline

Definition at line 122 of file tecs.h.

References _pitch_speed_weight.

Referenced by FixedwingPositionControl::control_position(), and FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_speedrate_p()

void TECS::set_speedrate_p ( float  speedrate_p)
inline

Definition at line 123 of file tecs.h.

References _speed_error_gain.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_throttle_damp()

void TECS::set_throttle_damp ( float  throttle_damp)
inline

Definition at line 126 of file tecs.h.

References _throttle_damping_gain.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_throttle_slewrate()

void TECS::set_throttle_slewrate ( float  slewrate)
inline

Definition at line 127 of file tecs.h.

References _throttle_slewrate.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_time_const()

void TECS::set_time_const ( float  time_const)
inline

Definition at line 104 of file tecs.h.

References _pitch_time_constant.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_time_const_throt()

void TECS::set_time_const_throt ( float  time_const_throt)
inline

Definition at line 125 of file tecs.h.

References _throttle_time_constant.

Referenced by FixedwingPositionControl::control_landing(), FixedwingPositionControl::control_position(), and FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ set_vertical_accel_limit()

void TECS::set_vertical_accel_limit ( float  limit)
inline

Definition at line 119 of file tecs.h.

References _vert_accel_limit.

Referenced by FixedwingPositionControl::init().

Here is the caller graph for this function:

◆ speed_derivative()

float TECS::speed_derivative ( )
inline

Definition at line 145 of file tecs.h.

References _speed_derivative.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ STE_error()

float TECS::STE_error ( )
inline

Definition at line 147 of file tecs.h.

References _STE_error.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ STE_rate_error()

float TECS::STE_rate_error ( )
inline

Definition at line 148 of file tecs.h.

References _STE_rate_error.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ TAS_rate_setpoint()

float TECS::TAS_rate_setpoint ( )
inline

Definition at line 144 of file tecs.h.

References _TAS_rate_setpoint.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ TAS_setpoint_adj()

float TECS::TAS_setpoint_adj ( )
inline

Definition at line 138 of file tecs.h.

References _TAS_setpoint_adj.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ tas_state()

float TECS::tas_state ( )
inline

Definition at line 139 of file tecs.h.

References _tas_state.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ tecs_mode()

ECL_TECS_MODE TECS::tecs_mode ( )
inline

Definition at line 133 of file tecs.h.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ throttle_integ_state()

float TECS::throttle_integ_state ( )
inline

Definition at line 153 of file tecs.h.

References _throttle_integ_state.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ timestamp()

uint64_t TECS::timestamp ( )
inline

Definition at line 132 of file tecs.h.

References _pitch_update_timestamp.

◆ update_pitch_throttle()

void TECS::update_pitch_throttle ( const matrix::Dcmf rotMat,
float  pitch,
float  baro_altitude,
float  hgt_setpoint,
float  EAS_setpoint,
float  indicated_airspeed,
float  eas_to_tas,
bool  climb_out_setpoint,
float  pitch_min_climbout,
float  throttle_min,
float  throttle_setpoint_max,
float  throttle_cruise,
float  pitch_limit_min,
float  pitch_limit_max 
)

Update the control loop calculations.

Definition at line 582 of file tecs.cpp.

References _climbout_mode_active, _detect_uncommanded_descent(), _detect_underspeed(), _dt, _in_air, _initialize_states(), _pitch_setpoint_max, _pitch_setpoint_min, _pitch_update_timestamp, _throttle_setpoint_max, _throttle_setpoint_min, _uncommanded_descent_recovery, _underspeed_detected, _update_energy_estimates(), _update_height_setpoint(), _update_pitch_setpoint(), _update_speed_setpoint(), _update_speed_states(), _update_STE_rate_lim(), _update_throttle_setpoint(), math::constrain(), DT_MAX, DT_MIN, ecl_absolute_time, ECL_TECS_MODE_BAD_DESCENT, ECL_TECS_MODE_CLIMBOUT, ECL_TECS_MODE_NORMAL, ECL_TECS_MODE_UNDERSPEED, and f().

Referenced by enable_airspeed(), and FixedwingPositionControl::tecs_update_pitch_throttle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ update_vehicle_state_estimates()

void TECS::update_vehicle_state_estimates ( float  airspeed,
const matrix::Dcmf rotMat,
const matrix::Vector3f accel_body,
bool  altitude_lock,
bool  in_air,
float  altitude,
bool  vz_valid,
float  vz,
float  az 
)

Updates the following vehicle kineamtic state estimates: Vertical position, velocity and acceleration.

Speed derivative Must be called prior to udating tecs control loops Must be called at 50Hz or greater

Definition at line 57 of file tecs.cpp.

References _EAS, _hgt_estimate_freq, _in_air, _speed_derivative, _state_update_timestamp, _states_initalized, _vert_accel_state, _vert_pos_state, _vert_vel_state, airspeed_sensor_enabled(), CONSTANTS_ONE_G, math::constrain(), dt, DT_DEFAULT, DT_MAX, DT_MIN, ecl_absolute_time, f(), and ISFINITE.

Referenced by enable_airspeed(), and FixedwingPositionControl::tecs_update_pitch_throttle().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ vert_pos_state()

float TECS::vert_pos_state ( )
inline

Definition at line 136 of file tecs.h.

References _vert_pos_state.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

◆ vert_vel_state()

float TECS::vert_vel_state ( )
inline

Definition at line 142 of file tecs.h.

References _vert_vel_state.

Referenced by FixedwingPositionControl::tecs_status_publish().

Here is the caller graph for this function:

Member Data Documentation

◆ _airspeed_enabled

bool TECS::_airspeed_enabled {false}
private

true when airspeed use has been enabled

Definition at line 276 of file tecs.h.

Referenced by airspeed_sensor_enabled(), and enable_airspeed().

◆ _climbout_mode_active

bool TECS::_climbout_mode_active {false}
private

true when in climbout mode

Definition at line 275 of file tecs.h.

Referenced by _initialize_states(), _update_pitch_setpoint(), _update_throttle_setpoint(), and update_pitch_throttle().

◆ _detect_underspeed_enabled

bool TECS::_detect_underspeed_enabled {true}
private

true when underspeed detection is enabled

Definition at line 273 of file tecs.h.

Referenced by _detect_underspeed(), and set_detect_underspeed_enabled().

◆ _dt

float TECS::_dt {DT_DEFAULT}
private

Time since last update of main TECS loop (sec)

Definition at line 268 of file tecs.h.

Referenced by _initialize_states(), _update_height_setpoint(), _update_pitch_setpoint(), _update_throttle_setpoint(), and update_pitch_throttle().

◆ _EAS

float TECS::_EAS {0.0f}
private

equivalent airspeed (m/sec)

Definition at line 225 of file tecs.h.

Referenced by _initialize_states(), _update_speed_states(), and update_vehicle_state_estimates().

◆ _EAS_setpoint

float TECS::_EAS_setpoint {0.0f}
private

Equivalent airspeed demand (m/sec)

Definition at line 230 of file tecs.h.

Referenced by _update_speed_states().

◆ _height_error_gain

float TECS::_height_error_gain {0.0f}
private

gain from height error to demanded climb rate (1/sec)

Definition at line 199 of file tecs.h.

Referenced by _update_height_setpoint(), and set_heightrate_p().

◆ _height_setpoint_gain_ff

float TECS::_height_setpoint_gain_ff {0.0f}
private

gain from height demand derivative to demanded climb rate

Definition at line 200 of file tecs.h.

Referenced by _update_height_setpoint(), and set_heightrate_ff().

◆ _hgt_estimate_freq

float TECS::_hgt_estimate_freq {0.0f}
private

cross-over frequency of the height rate complementary filter (rad/sec)

Definition at line 186 of file tecs.h.

Referenced by set_height_comp_filter_omega(), and update_vehicle_state_estimates().

◆ _hgt_rate_setpoint

float TECS::_hgt_rate_setpoint {0.0f}
private

demanded climb rate tracked by the TECS algorithm

Definition at line 240 of file tecs.h.

Referenced by _update_energy_estimates(), _update_height_setpoint(), and hgt_rate_setpoint().

◆ _hgt_setpoint

float TECS::_hgt_setpoint {0.0f}
private

demanded height tracked by the TECS algorithm (m)

Definition at line 235 of file tecs.h.

Referenced by _update_height_setpoint().

◆ _hgt_setpoint_adj

float TECS::_hgt_setpoint_adj {0.0f}
private

demanded height used by the control loops after all filtering has been applied (m)

Definition at line 238 of file tecs.h.

Referenced by _detect_underspeed(), _initialize_states(), _update_energy_estimates(), _update_height_setpoint(), and hgt_setpoint_adj().

◆ _hgt_setpoint_adj_prev

float TECS::_hgt_setpoint_adj_prev {0.0f}
private

value of _hgt_setpoint_adj from previous frame (m)

Definition at line 239 of file tecs.h.

Referenced by _initialize_states(), _update_height_setpoint(), and handle_alt_step().

◆ _hgt_setpoint_in_prev

float TECS::_hgt_setpoint_in_prev {0.0f}
private

previous value of _hgt_setpoint after noise filtering (m)

Definition at line 236 of file tecs.h.

Referenced by _initialize_states(), _update_height_setpoint(), and handle_alt_step().

◆ _hgt_setpoint_prev

float TECS::_hgt_setpoint_prev {0.0f}
private

previous value of _hgt_setpoint after noise filtering and rate limiting (m)

Definition at line 237 of file tecs.h.

Referenced by _initialize_states(), _update_height_setpoint(), and handle_alt_step().

◆ _in_air

bool TECS::_in_air {false}
private

true when the vehicle is flying

Definition at line 278 of file tecs.h.

Referenced by _initialize_states(), _update_speed_states(), update_pitch_throttle(), and update_vehicle_state_estimates().

◆ _indicated_airspeed_max

float TECS::_indicated_airspeed_max {30.0f}
private

equivalent airspeed demand upper limit (m/sec)

Definition at line 203 of file tecs.h.

Referenced by _update_speed_states(), and set_indicated_airspeed_max().

◆ _indicated_airspeed_min

float TECS::_indicated_airspeed_min {3.0f}
private

equivalent airspeed demand lower limit (m/sec)

Definition at line 202 of file tecs.h.

Referenced by _update_speed_states(), and set_indicated_airspeed_min().

◆ _integrator_gain

float TECS::_integrator_gain {0.0f}
private

integrator gain used by the throttle and pitch demand calculation

Definition at line 195 of file tecs.h.

Referenced by _update_pitch_setpoint(), _update_throttle_setpoint(), and set_integrator_gain().

◆ _last_pitch_setpoint

float TECS::_last_pitch_setpoint {0.0f}
private

pitch demand rate limiter state (rad/sec)

Definition at line 221 of file tecs.h.

Referenced by _initialize_states(), and _update_pitch_setpoint().

◆ _last_throttle_setpoint

float TECS::_last_throttle_setpoint {0.0f}
private

throttle demand rate limiter state (1/sec)

Definition at line 220 of file tecs.h.

Referenced by _initialize_states(), and _update_throttle_setpoint().

◆ _load_factor_correction

float TECS::_load_factor_correction {0.0f}
private

gain from normal load factor increase to total energy rate demand (m**2/sec**3)

Definition at line 197 of file tecs.h.

Referenced by _update_throttle_setpoint(), and set_roll_throttle_compensation().

◆ _max_climb_rate

float TECS::_max_climb_rate {2.0f}
private

climb rate produced by max allowed throttle (m/sec)

Definition at line 188 of file tecs.h.

Referenced by _update_height_setpoint(), _update_STE_rate_lim(), and set_max_climb_rate().

◆ _max_sink_rate

float TECS::_max_sink_rate {2.0f}
private

maximum safe sink rate (m/sec)

Definition at line 190 of file tecs.h.

Referenced by _update_height_setpoint(), and set_max_sink_rate().

◆ _min_sink_rate

float TECS::_min_sink_rate {1.0f}
private

sink rate produced by min allowed throttle (m/sec)

Definition at line 189 of file tecs.h.

Referenced by _update_STE_rate_lim(), and set_min_sink_rate().

◆ _pitch_damping_gain

float TECS::_pitch_damping_gain {0.0f}
private

damping gain of the pitch demand calculation (sec)

Definition at line 193 of file tecs.h.

Referenced by _update_pitch_setpoint(), and set_pitch_damping().

◆ _pitch_integ_state

float TECS::_pitch_integ_state {0.0f}
private

pitch integrator state (rad)

Definition at line 219 of file tecs.h.

Referenced by _initialize_states(), _update_pitch_setpoint(), and pitch_integ_state().

◆ _pitch_setpoint

float TECS::_pitch_setpoint {0.0f}
private

pitch angle demand (radians)

Definition at line 208 of file tecs.h.

Referenced by _update_pitch_setpoint(), and get_pitch_setpoint().

◆ _pitch_setpoint_max

float TECS::_pitch_setpoint_max {0.5f}
private

pitch demand upper limit (rad)

Definition at line 248 of file tecs.h.

Referenced by _initialize_states(), _update_pitch_setpoint(), and update_pitch_throttle().

◆ _pitch_setpoint_min

float TECS::_pitch_setpoint_min {-0.5f}
private

pitch demand lower limit (rad)

Definition at line 249 of file tecs.h.

Referenced by _initialize_states(), _update_pitch_setpoint(), and update_pitch_throttle().

◆ _pitch_setpoint_unc

float TECS::_pitch_setpoint_unc {0.0f}
private

pitch demand before limiting (rad)

Definition at line 243 of file tecs.h.

Referenced by _initialize_states(), and _update_pitch_setpoint().

◆ _pitch_speed_weight

float TECS::_pitch_speed_weight {1.0f}
private

speed control weighting used by pitch demand calculation

Definition at line 198 of file tecs.h.

Referenced by _update_pitch_setpoint(), get_speed_weight(), and set_speed_weight().

◆ _pitch_time_constant

float TECS::_pitch_time_constant {5.0f}
private

control time constant used by the pitch demand calculation (sec)

Definition at line 191 of file tecs.h.

Referenced by _update_pitch_setpoint(), and set_time_const().

◆ _pitch_update_timestamp

uint64_t TECS::_pitch_update_timestamp {0}
private

last timestamp of the pitch function call

Definition at line 183 of file tecs.h.

Referenced by _initialize_states(), timestamp(), and update_pitch_throttle().

◆ _SEB_error

float TECS::_SEB_error {0.0f}
private

specific energy balance error (m**2/sec**2)

Definition at line 264 of file tecs.h.

Referenced by _update_pitch_setpoint(), and SEB_error().

◆ _SEB_rate_error

float TECS::_SEB_rate_error {0.0f}
private

specific energy balance rate error (m**2/sec**3)

Definition at line 265 of file tecs.h.

Referenced by _update_pitch_setpoint(), and SEB_rate_error().

◆ _SKE_estimate

float TECS::_SKE_estimate {0.0f}
private

specific kinetic energy estimate (m**2/sec**2)

Definition at line 257 of file tecs.h.

Referenced by _update_energy_estimates(), _update_pitch_setpoint(), and _update_throttle_setpoint().

◆ _SKE_rate

float TECS::_SKE_rate {0.0f}
private

specific kinetic energy rate estimate (m**2/sec**3)

Definition at line 259 of file tecs.h.

Referenced by _detect_uncommanded_descent(), _update_energy_estimates(), _update_pitch_setpoint(), and _update_throttle_setpoint().

◆ _SKE_rate_setpoint

float TECS::_SKE_rate_setpoint {0.0f}
private

specific kinetic energy rate demand (m**2/sec**3)

Definition at line 255 of file tecs.h.

Referenced by _update_energy_estimates(), _update_pitch_setpoint(), and _update_throttle_setpoint().

◆ _SKE_setpoint

float TECS::_SKE_setpoint {0.0f}
private

specific kinetic energy demand (m**2/sec**2)

Definition at line 253 of file tecs.h.

Referenced by _update_energy_estimates(), _update_pitch_setpoint(), and _update_throttle_setpoint().

◆ _SPE_estimate

float TECS::_SPE_estimate {0.0f}
private

specific potential energy estimate (m**2/sec**2)

Definition at line 256 of file tecs.h.

Referenced by _update_energy_estimates(), _update_pitch_setpoint(), and _update_throttle_setpoint().

◆ _SPE_rate

float TECS::_SPE_rate {0.0f}
private

specific potential energy rate estimate (m**2/sec**3)

Definition at line 258 of file tecs.h.

Referenced by _detect_uncommanded_descent(), _update_energy_estimates(), _update_pitch_setpoint(), and _update_throttle_setpoint().

◆ _SPE_rate_setpoint

float TECS::_SPE_rate_setpoint {0.0f}
private

specific potential energy rate demand (m**2/sec**3)

Definition at line 254 of file tecs.h.

Referenced by _update_energy_estimates(), _update_pitch_setpoint(), and _update_throttle_setpoint().

◆ _SPE_setpoint

float TECS::_SPE_setpoint {0.0f}
private

specific potential energy demand (m**2/sec**2)

Definition at line 252 of file tecs.h.

Referenced by _update_energy_estimates(), _update_pitch_setpoint(), and _update_throttle_setpoint().

◆ _speed_derivative

float TECS::_speed_derivative {0.0f}
private

rate of change of speed along X axis (m/sec**2)

Definition at line 222 of file tecs.h.

Referenced by _update_energy_estimates(), _update_speed_states(), speed_derivative(), and update_vehicle_state_estimates().

◆ _speed_error_gain

float TECS::_speed_error_gain {0.0f}
private

gain from speed error to demanded speed rate (1/sec)

Definition at line 201 of file tecs.h.

Referenced by _update_speed_setpoint(), and set_speedrate_p().

◆ _speed_update_timestamp

uint64_t TECS::_speed_update_timestamp {0}
private

last timestamp of the speed function call

Definition at line 182 of file tecs.h.

Referenced by _update_speed_states().

◆ _state_update_timestamp

uint64_t TECS::_state_update_timestamp {0}
private

last timestamp of the 50 Hz function call

Definition at line 181 of file tecs.h.

Referenced by update_vehicle_state_estimates().

◆ _states_initalized

bool TECS::_states_initalized {false}
private

true when TECS states have been iniitalized

Definition at line 277 of file tecs.h.

Referenced by _initialize_states(), reset_state(), and update_vehicle_state_estimates().

◆ _STE_error

float TECS::_STE_error {0.0f}
private

specific total energy error (m**2/sec**2)

Definition at line 262 of file tecs.h.

Referenced by _detect_uncommanded_descent(), _update_throttle_setpoint(), and STE_error().

◆ _STE_rate_error

float TECS::_STE_rate_error {0.0f}
private

specific total energy rate error (m**2/sec**3)

Definition at line 263 of file tecs.h.

Referenced by _initialize_states(), _update_throttle_setpoint(), and STE_rate_error().

◆ _STE_rate_max

float TECS::_STE_rate_max {0.0f}
private

specific total energy rate upper limit achieved when throttle is at _throttle_setpoint_max (m**2/sec**3)

Definition at line 244 of file tecs.h.

Referenced by _update_speed_setpoint(), _update_STE_rate_lim(), and _update_throttle_setpoint().

◆ _STE_rate_min

float TECS::_STE_rate_min {0.0f}
private

specific total energy rate lower limit acheived when throttle is at _throttle_setpoint_min (m**2/sec**3)

Definition at line 245 of file tecs.h.

Referenced by _update_speed_setpoint(), _update_STE_rate_lim(), and _update_throttle_setpoint().

◆ _tas_estimate_freq

float TECS::_tas_estimate_freq {0.0f}
private

cross-over frequency of the true airspeed complementary filter (rad/sec)

Definition at line 187 of file tecs.h.

Referenced by _update_speed_states(), and set_speed_comp_filter_omega().

◆ _TAS_max

float TECS::_TAS_max {30.0f}
private

true airpeed demand upper limit (m/sec)

Definition at line 226 of file tecs.h.

Referenced by _update_speed_setpoint(), and _update_speed_states().

◆ _TAS_min

float TECS::_TAS_min {3.0f}
private

true airpeed demand lower limit (m/sec)

Definition at line 227 of file tecs.h.

Referenced by _detect_underspeed(), _update_speed_setpoint(), and _update_speed_states().

◆ _TAS_rate_setpoint

float TECS::_TAS_rate_setpoint {0.0f}
private

true airspeed rate demand tracked by the TECS algorithm (m/sec**2)

Definition at line 232 of file tecs.h.

Referenced by _update_energy_estimates(), _update_speed_setpoint(), and TAS_rate_setpoint().

◆ _tas_rate_state

float TECS::_tas_rate_state {0.0f}
private

complimentary filter state - true airspeed first derivative (m/sec**2)

Definition at line 214 of file tecs.h.

Referenced by _initialize_states(), and _update_speed_states().

◆ _TAS_setpoint

float TECS::_TAS_setpoint {0.0f}
private

current airpeed demand (m/sec)

Definition at line 228 of file tecs.h.

Referenced by _update_speed_setpoint(), and _update_speed_states().

◆ _TAS_setpoint_adj

float TECS::_TAS_setpoint_adj {0.0f}
private

true airspeed demand tracked by the TECS algorithm (m/sec)

Definition at line 231 of file tecs.h.

Referenced by _initialize_states(), _update_energy_estimates(), _update_speed_setpoint(), and TAS_setpoint_adj().

◆ _TAS_setpoint_last

float TECS::_TAS_setpoint_last {0.0f}
private

previous true airpeed demand (m/sec)

Definition at line 229 of file tecs.h.

Referenced by _initialize_states().

◆ _tas_state

float TECS::_tas_state {0.0f}
private

complimentary filter state - true airspeed (m/sec)

Definition at line 215 of file tecs.h.

Referenced by _detect_underspeed(), _initialize_states(), _update_energy_estimates(), _update_pitch_setpoint(), _update_speed_setpoint(), _update_speed_states(), and tas_state().

◆ _throttle_damping_gain

float TECS::_throttle_damping_gain {0.0f}
private

damping gain of the throttle demand calculation (sec)

Definition at line 194 of file tecs.h.

Referenced by _update_throttle_setpoint(), and set_throttle_damp().

◆ _throttle_integ_state

float TECS::_throttle_integ_state {0.0f}
private

throttle integrator state

Definition at line 218 of file tecs.h.

Referenced by _initialize_states(), _update_throttle_setpoint(), and throttle_integ_state().

◆ _throttle_setpoint

float TECS::_throttle_setpoint {0.0f}
private

normalized throttle demand (0..1)

Definition at line 207 of file tecs.h.

Referenced by _detect_uncommanded_descent(), _detect_underspeed(), _update_throttle_setpoint(), and get_throttle_setpoint().

◆ _throttle_setpoint_max

float TECS::_throttle_setpoint_max {0.0f}
private

normalised throttle upper limit

Definition at line 246 of file tecs.h.

Referenced by _detect_uncommanded_descent(), _detect_underspeed(), _initialize_states(), _update_throttle_setpoint(), and update_pitch_throttle().

◆ _throttle_setpoint_min

float TECS::_throttle_setpoint_min {0.0f}
private

normalised throttle lower limit

Definition at line 247 of file tecs.h.

Referenced by _initialize_states(), _update_throttle_setpoint(), and update_pitch_throttle().

◆ _throttle_slewrate

float TECS::_throttle_slewrate {0.0f}
private

throttle demand slew rate limit (1/sec)

Definition at line 204 of file tecs.h.

Referenced by _update_throttle_setpoint(), and set_throttle_slewrate().

◆ _throttle_time_constant

float TECS::_throttle_time_constant {8.0f}
private

control time constant used by the throttle demand calculation (sec)

Definition at line 192 of file tecs.h.

Referenced by _update_throttle_setpoint(), and set_time_const_throt().

◆ _uncommanded_descent_recovery

bool TECS::_uncommanded_descent_recovery {false}
private

true when a continuous descent caused by an unachievable airspeed demand has been detected

Definition at line 274 of file tecs.h.

Referenced by _detect_uncommanded_descent(), _initialize_states(), _update_speed_setpoint(), and update_pitch_throttle().

◆ _underspeed_detected

bool TECS::_underspeed_detected {false}
private

◆ _vert_accel_limit

float TECS::_vert_accel_limit {0.0f}
private

magnitude of the maximum vertical acceleration allowed (m/sec**2)

Definition at line 196 of file tecs.h.

Referenced by _update_pitch_setpoint(), and set_vertical_accel_limit().

◆ _vert_accel_state

float TECS::_vert_accel_state {0.0f}
private

complimentary filter state - height second derivative (m/sec**2)

Definition at line 211 of file tecs.h.

Referenced by _initialize_states(), handle_alt_step(), and update_vehicle_state_estimates().

◆ _vert_pos_state

float TECS::_vert_pos_state {0.0f}
private

complimentary filter state - height (m)

Definition at line 213 of file tecs.h.

Referenced by _detect_underspeed(), _initialize_states(), _update_energy_estimates(), handle_alt_step(), update_vehicle_state_estimates(), and vert_pos_state().

◆ _vert_vel_state

float TECS::_vert_vel_state {0.0f}
private

complimentary filter state - height rate (m/sec)

Definition at line 212 of file tecs.h.

Referenced by _initialize_states(), _update_energy_estimates(), handle_alt_step(), update_vehicle_state_estimates(), and vert_vel_state().

◆ DT_DEFAULT

constexpr float TECS::DT_DEFAULT = 0.02f
staticprivate

default value for _dt (sec)

Definition at line 269 of file tecs.h.

Referenced by _initialize_states(), and update_vehicle_state_estimates().


The documentation for this class was generated from the following files: