PX4 Firmware
PX4 Autopilot Software http://px4.io
|
#include <tecs.h>
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 | |
TECS & | operator= (const TECS &)=delete |
TECS (TECS &&)=delete | |
TECS & | operator= (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... | |
enum TECS::ECL_TECS_MODE |
|
default |
|
default |
|
delete |
|
delete |
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
inline |
Get the current airspeed status.
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().
|
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().
|
inline |
Definition at line 89 of file tecs.h.
References _pitch_setpoint.
Referenced by FixedwingPositionControl::get_tecs_pitch().
|
inline |
Definition at line 90 of file tecs.h.
References _pitch_speed_weight.
|
inline |
Definition at line 88 of file tecs.h.
References _throttle_setpoint.
Referenced by FixedwingPositionControl::get_tecs_thrust().
|
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().
|
inline |
Definition at line 141 of file tecs.h.
References _hgt_rate_setpoint.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 135 of file tecs.h.
References _hgt_setpoint_adj.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 154 of file tecs.h.
References _pitch_integ_state.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 92 of file tecs.h.
References _states_initalized.
Referenced by FixedwingPositionControl::control_position(), and FixedwingPositionControl::tecs_update_pitch_throttle().
|
inline |
Definition at line 150 of file tecs.h.
References _SEB_error.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 151 of file tecs.h.
References _SEB_rate_error.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 101 of file tecs.h.
References _detect_underspeed_enabled.
Referenced by FixedwingPositionControl::tecs_update_pitch_throttle().
|
inline |
Definition at line 111 of file tecs.h.
References _hgt_estimate_freq.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 112 of file tecs.h.
References _height_setpoint_gain_ff.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 113 of file tecs.h.
References _height_error_gain.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 115 of file tecs.h.
References _indicated_airspeed_max.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 116 of file tecs.h.
References _indicated_airspeed_min.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 105 of file tecs.h.
References _integrator_gain.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 109 of file tecs.h.
References _max_climb_rate.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 108 of file tecs.h.
References _max_sink_rate.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 107 of file tecs.h.
References _min_sink_rate.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 118 of file tecs.h.
References _pitch_damping_gain.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 129 of file tecs.h.
References _load_factor_correction.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 121 of file tecs.h.
References _tas_estimate_freq.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 122 of file tecs.h.
References _pitch_speed_weight.
Referenced by FixedwingPositionControl::control_position(), and FixedwingPositionControl::init().
|
inline |
Definition at line 123 of file tecs.h.
References _speed_error_gain.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 126 of file tecs.h.
References _throttle_damping_gain.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 127 of file tecs.h.
References _throttle_slewrate.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 104 of file tecs.h.
References _pitch_time_constant.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 125 of file tecs.h.
References _throttle_time_constant.
Referenced by FixedwingPositionControl::control_landing(), FixedwingPositionControl::control_position(), and FixedwingPositionControl::init().
|
inline |
Definition at line 119 of file tecs.h.
References _vert_accel_limit.
Referenced by FixedwingPositionControl::init().
|
inline |
Definition at line 145 of file tecs.h.
References _speed_derivative.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 147 of file tecs.h.
References _STE_error.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 148 of file tecs.h.
References _STE_rate_error.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 144 of file tecs.h.
References _TAS_rate_setpoint.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 138 of file tecs.h.
References _TAS_setpoint_adj.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 139 of file tecs.h.
References _tas_state.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 133 of file tecs.h.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 153 of file tecs.h.
References _throttle_integ_state.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 132 of file tecs.h.
References _pitch_update_timestamp.
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().
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().
|
inline |
Definition at line 136 of file tecs.h.
References _vert_pos_state.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
inline |
Definition at line 142 of file tecs.h.
References _vert_vel_state.
Referenced by FixedwingPositionControl::tecs_status_publish().
|
private |
true when airspeed use has been enabled
Definition at line 276 of file tecs.h.
Referenced by airspeed_sensor_enabled(), and enable_airspeed().
|
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().
|
private |
true when underspeed detection is enabled
Definition at line 273 of file tecs.h.
Referenced by _detect_underspeed(), and set_detect_underspeed_enabled().
|
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().
|
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().
|
private |
Equivalent airspeed demand (m/sec)
Definition at line 230 of file tecs.h.
Referenced by _update_speed_states().
|
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().
|
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().
|
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().
|
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().
|
private |
demanded height tracked by the TECS algorithm (m)
Definition at line 235 of file tecs.h.
Referenced by _update_height_setpoint().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
private |
pitch demand rate limiter state (rad/sec)
Definition at line 221 of file tecs.h.
Referenced by _initialize_states(), and _update_pitch_setpoint().
|
private |
throttle demand rate limiter state (1/sec)
Definition at line 220 of file tecs.h.
Referenced by _initialize_states(), and _update_throttle_setpoint().
|
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().
|
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().
|
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().
|
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().
|
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().
|
private |
pitch integrator state (rad)
Definition at line 219 of file tecs.h.
Referenced by _initialize_states(), _update_pitch_setpoint(), and pitch_integ_state().
|
private |
pitch angle demand (radians)
Definition at line 208 of file tecs.h.
Referenced by _update_pitch_setpoint(), and get_pitch_setpoint().
|
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().
|
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().
|
private |
pitch demand before limiting (rad)
Definition at line 243 of file tecs.h.
Referenced by _initialize_states(), and _update_pitch_setpoint().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
private |
last timestamp of the speed function call
Definition at line 182 of file tecs.h.
Referenced by _update_speed_states().
|
private |
last timestamp of the 50 Hz function call
Definition at line 181 of file tecs.h.
Referenced by update_vehicle_state_estimates().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
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().
|
private |
current airpeed demand (m/sec)
Definition at line 228 of file tecs.h.
Referenced by _update_speed_setpoint(), and _update_speed_states().
|
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().
|
private |
previous true airpeed demand (m/sec)
Definition at line 229 of file tecs.h.
Referenced by _initialize_states().
|
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().
|
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().
|
private |
throttle integrator state
Definition at line 218 of file tecs.h.
Referenced by _initialize_states(), _update_throttle_setpoint(), and throttle_integ_state().
|
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().
|
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().
|
private |
normalised throttle lower limit
Definition at line 247 of file tecs.h.
Referenced by _initialize_states(), _update_throttle_setpoint(), and update_pitch_throttle().
|
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().
|
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().
|
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().
|
private |
true when an underspeed condition has been detected
Definition at line 272 of file tecs.h.
Referenced by _detect_uncommanded_descent(), _detect_underspeed(), _initialize_states(), _update_pitch_setpoint(), _update_speed_setpoint(), _update_throttle_setpoint(), and update_pitch_throttle().
|
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().
|
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().
|
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().
|
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().
|
staticprivate |
default value for _dt (sec)
Definition at line 269 of file tecs.h.
Referenced by _initialize_states(), and update_vehicle_state_estimates().