aboutsummaryrefslogtreecommitdiff
path: root/src/lib/external_lgpl/tecs/tecs.h
diff options
context:
space:
mode:
Diffstat (limited to 'src/lib/external_lgpl/tecs/tecs.h')
-rw-r--r--src/lib/external_lgpl/tecs/tecs.h45
1 files changed, 27 insertions, 18 deletions
diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h
index f8f832ed7..5cafb1c79 100644
--- a/src/lib/external_lgpl/tecs/tecs.h
+++ b/src/lib/external_lgpl/tecs/tecs.h
@@ -28,16 +28,7 @@ class __EXPORT TECS
{
public:
TECS() :
-
- _airspeed_enabled(false),
- _throttle_slewrate(0.0f),
- _climbOutDem(false),
- _hgt_dem_prev(0.0f),
- _hgt_dem_adj_last(0.0f),
- _hgt_dem_in_old(0.0f),
- _TAS_dem_last(0.0f),
- _TAS_dem_adj(0.0f),
- _TAS_dem(0.0f),
+ _pitch_dem(0.0f),
_integ1_state(0.0f),
_integ2_state(0.0f),
_integ3_state(0.0f),
@@ -45,8 +36,16 @@ public:
_integ5_state(0.0f),
_integ6_state(0.0f),
_integ7_state(0.0f),
- _pitch_dem(0.0f),
_last_pitch_dem(0.0f),
+ _vel_dot(0.0f),
+ _TAS_dem(0.0f),
+ _TAS_dem_last(0.0f),
+ _hgt_dem_in_old(0.0f),
+ _hgt_dem_adj_last(0.0f),
+ _hgt_dem_prev(0.0f),
+ _TAS_dem_adj(0.0f),
+ _STEdotErrLast(0.0f),
+ _climbOutDem(false),
_SPE_dem(0.0f),
_SKE_dem(0.0f),
_SPEdot_dem(0.0f),
@@ -55,9 +54,9 @@ public:
_SKE_est(0.0f),
_SPEdot(0.0f),
_SKEdot(0.0f),
- _vel_dot(0.0f),
- _STEdotErrLast(0.0f) {
-
+ _airspeed_enabled(false),
+ _throttle_slewrate(0.0f)
+ {
}
bool airspeed_sensor_enabled() {
@@ -71,10 +70,10 @@ public:
// Update of the estimated height and height rate internal state
// Update of the inertial speed rate internal state
// Should be called at 50Hz or greater
- void update_50hz(float baro_altitude, float airspeed, const math::Dcm &rotMat, const math::Vector3 &accel_body, const math::Vector3 &accel_earth);
+ void update_50hz(float baro_altitude, float airspeed, const math::Matrix<3,3> &rotMat, const math::Vector<3> &accel_body, const math::Vector<3> &accel_earth);
// Update the control loop calculations
- void update_pitch_throttle(const math::Dcm &rotMat, float pitch, float baro_altitude, float hgt_dem, float EAS_dem, float indicated_airspeed, float EAS2TAS, bool climbOutDem, float ptchMinCO,
+ void update_pitch_throttle(const math::Matrix<3,3> &rotMat, float pitch, float baro_altitude, float hgt_dem, float EAS_dem, float indicated_airspeed, float EAS2TAS, bool climbOutDem, float ptchMinCO,
float throttle_min, float throttle_max, float throttle_cruise,
float pitch_limit_min, float pitch_limit_max);
// demanded throttle in percentage
@@ -180,6 +179,14 @@ public:
_indicated_airspeed_max = airspeed;
}
+ void set_heightrate_p(float heightrate_p) {
+ _heightrate_p = heightrate_p;
+ }
+
+ void set_speedrate_p(float speedrate_p) {
+ _speedrate_p = speedrate_p;
+ }
+
private:
// Last time update_50Hz was called
uint64_t _update_50hz_last_usec;
@@ -203,6 +210,8 @@ private:
float _vertAccLim;
float _rollComp;
float _spdWeight;
+ float _heightrate_p;
+ float _speedrate_p;
// throttle demand in the range from 0.0 to 1.0
float _throttle_dem;
@@ -329,7 +338,7 @@ private:
void _update_speed_demand(void);
// Update the demanded height
- void _update_height_demand(float demand);
+ void _update_height_demand(float demand, float state);
// Detect an underspeed condition
void _detect_underspeed(void);
@@ -338,7 +347,7 @@ private:
void _update_energies(void);
// Update Demanded Throttle
- void _update_throttle(float throttle_cruise, const math::Dcm &rotMat);
+ void _update_throttle(float throttle_cruise, const math::Matrix<3,3> &rotMat);
// Detect Bad Descent
void _detect_bad_descent(void);