Skip to content

Commit ba13bb7

Browse files
RomanBapstJaeyoung-Lim
authored andcommitted
tecs: propagate altitude setpoint based on target climb/sink rate
- avoids tecs always climbing and sinking and max rates and allows to fine tune these rates - avoid numerical calculation of feedforward velocity using derivative, this was prone to jitter in dt Signed-off-by: RomanBapst <[email protected]>
1 parent f73cf48 commit ba13bb7

File tree

4 files changed

+37
-65
lines changed

4 files changed

+37
-65
lines changed

src/lib/tecs/TECS.cpp

Lines changed: 25 additions & 50 deletions
Original file line numberDiff line numberDiff line change
@@ -174,51 +174,31 @@ void TECS::_update_speed_setpoint()
174174

175175
}
176176

177-
void TECS::_update_height_setpoint(float desired, float state)
177+
void TECS::updateHeightRateSetpoint(float alt_sp_amsl_m, float target_climbrate_m_s, float target_sinkrate_m_s,
178+
float alt_amsl)
178179
{
179-
// Detect first time through and initialize previous value to demand
180-
if (PX4_ISFINITE(desired) && fabsf(_hgt_setpoint_in_prev) < 0.1f) {
181-
_hgt_setpoint_in_prev = desired;
182-
}
183-
184-
// Apply a 2 point moving average to demanded height to reduce
185-
// intersampling noise effects.
186-
if (PX4_ISFINITE(desired)) {
187-
_hgt_setpoint = 0.5f * (desired + _hgt_setpoint_in_prev);
180+
target_climbrate_m_s = math::min(target_climbrate_m_s, _max_climb_rate);
181+
target_sinkrate_m_s = math::min(target_sinkrate_m_s, _max_sink_rate);
188182

189-
} else {
190-
_hgt_setpoint = _hgt_setpoint_in_prev;
191-
}
183+
float feedforward_height_rate = 0.0f;
192184

193-
_hgt_setpoint_in_prev = _hgt_setpoint;
185+
if (fabsf(alt_sp_amsl_m - _hgt_setpoint) < math::max(target_sinkrate_m_s, target_climbrate_m_s) * _dt) {
186+
_hgt_setpoint = alt_sp_amsl_m;
194187

195-
// Apply a rate limit to respect vehicle performance limitations
196-
if ((_hgt_setpoint - _hgt_setpoint_prev) > (_max_climb_rate * _dt)) {
197-
_hgt_setpoint = _hgt_setpoint_prev + _max_climb_rate * _dt;
188+
} else if (alt_sp_amsl_m > _hgt_setpoint) {
189+
_hgt_setpoint += target_climbrate_m_s * _dt;
190+
feedforward_height_rate = target_climbrate_m_s;
198191

199-
} else if ((_hgt_setpoint - _hgt_setpoint_prev) < (-_max_sink_rate * _dt)) {
200-
_hgt_setpoint = _hgt_setpoint_prev - _max_sink_rate * _dt;
192+
} else if (alt_sp_amsl_m < _hgt_setpoint) {
193+
_hgt_setpoint -= target_sinkrate_m_s * _dt;
194+
feedforward_height_rate = -target_sinkrate_m_s;
201195
}
202196

203-
_hgt_setpoint_prev = _hgt_setpoint;
204-
205-
// Apply a first order noise filter
206-
_hgt_setpoint_adj = 0.1f * _hgt_setpoint + 0.9f * _hgt_setpoint_adj_prev;
207-
208197
// Use a first order system to calculate a height rate setpoint from the current height error.
209198
// Additionally, allow to add feedforward from heigh setpoint change
210-
_hgt_rate_setpoint = (_hgt_setpoint_adj - state) * _height_error_gain + _height_setpoint_gain_ff *
211-
(_hgt_setpoint_adj - _hgt_setpoint_adj_prev) / _dt;
212-
213-
_hgt_setpoint_adj_prev = _hgt_setpoint_adj;
214-
215-
// Limit the rate of change of height demand to respect vehicle performance limits
216-
if (_hgt_rate_setpoint > _max_climb_rate) {
217-
_hgt_rate_setpoint = _max_climb_rate;
218-
219-
} else if (_hgt_rate_setpoint < -_max_sink_rate) {
220-
_hgt_rate_setpoint = -_max_sink_rate;
221-
}
199+
_hgt_rate_setpoint = (_hgt_setpoint - alt_amsl) * _height_error_gain + _height_setpoint_gain_ff *
200+
feedforward_height_rate;
201+
_hgt_rate_setpoint = math::constrain(_hgt_rate_setpoint, -_max_sink_rate, _max_climb_rate);
222202
}
223203

224204
void TECS::_detect_underspeed()
@@ -229,7 +209,7 @@ void TECS::_detect_underspeed()
229209
}
230210

231211
if (((_tas_state < _TAS_min * 0.9f) && (_last_throttle_setpoint >= _throttle_setpoint_max * 0.95f))
232-
|| ((_vert_pos_state < _hgt_setpoint_adj) && _underspeed_detected)) {
212+
|| ((_vert_pos_state < _hgt_setpoint) && _underspeed_detected)) {
233213

234214
_underspeed_detected = true;
235215

@@ -241,7 +221,7 @@ void TECS::_detect_underspeed()
241221
void TECS::_update_energy_estimates()
242222
{
243223
// Calculate specific energy demands in units of (m**2/sec**2)
244-
_SPE_setpoint = _hgt_setpoint_adj * CONSTANTS_ONE_G; // potential energy
224+
_SPE_setpoint = _hgt_setpoint * CONSTANTS_ONE_G; // potential energy
245225
_SKE_setpoint = 0.5f * _TAS_setpoint_adj * _TAS_setpoint_adj; // kinetic energy
246226

247227
// Calculate total energy error
@@ -477,10 +457,7 @@ void TECS::_initialize_states(float pitch, float throttle_cruise, float baro_alt
477457
_last_throttle_setpoint = (_in_air ? throttle_cruise : 0.0f);;
478458
_last_pitch_setpoint = constrain(pitch, _pitch_setpoint_min, _pitch_setpoint_max);
479459
_pitch_setpoint_unc = _last_pitch_setpoint;
480-
_hgt_setpoint_adj_prev = baro_altitude;
481-
_hgt_setpoint_adj = _hgt_setpoint_adj_prev;
482-
_hgt_setpoint_prev = _hgt_setpoint_adj_prev;
483-
_hgt_setpoint_in_prev = _hgt_setpoint_adj_prev;
460+
_hgt_setpoint = baro_altitude;
484461
_TAS_setpoint_last = _EAS * EAS2TAS;
485462
_TAS_setpoint_adj = _TAS_setpoint_last;
486463
_underspeed_detected = false;
@@ -499,15 +476,12 @@ void TECS::_initialize_states(float pitch, float throttle_cruise, float baro_alt
499476
// throttle lower limit is set to a value that prevents throttle reduction
500477
_throttle_setpoint_min = _throttle_setpoint_max - 0.01f;
501478

502-
// height demand and associated states are set to track the measured height
503-
_hgt_setpoint_adj_prev = baro_altitude;
504-
_hgt_setpoint_adj = _hgt_setpoint_adj_prev;
505-
_hgt_setpoint_prev = _hgt_setpoint_adj_prev;
506-
507479
// airspeed demand states are set to track the measured airspeed
508480
_TAS_setpoint_last = _EAS * EAS2TAS;
509481
_TAS_setpoint_adj = _EAS * EAS2TAS;
510482

483+
_hgt_setpoint = baro_altitude;
484+
511485
// disable speed and decent error condition checks
512486
_underspeed_detected = false;
513487
_uncommanded_descent_recovery = false;
@@ -535,7 +509,8 @@ void TECS::_update_STE_rate_lim()
535509

536510
void TECS::update_pitch_throttle(float pitch, float baro_altitude, float hgt_setpoint,
537511
float EAS_setpoint, float equivalent_airspeed, float eas_to_tas, bool climb_out_setpoint, float pitch_min_climbout,
538-
float throttle_min, float throttle_max, float throttle_cruise, float pitch_limit_min, float pitch_limit_max)
512+
float throttle_min, float throttle_max, float throttle_cruise, float pitch_limit_min, float pitch_limit_max,
513+
float target_climbrate, float target_sinkrate)
539514
{
540515
// Calculate the time since last update (seconds)
541516
uint64_t now = hrt_absolute_time();
@@ -573,8 +548,8 @@ void TECS::update_pitch_throttle(float pitch, float baro_altitude, float hgt_set
573548
// Calculate the demanded true airspeed
574549
_update_speed_setpoint();
575550

576-
// Calculate the demanded height
577-
_update_height_setpoint(hgt_setpoint, baro_altitude);
551+
// calculate heigh rate setpoint based on altitude demand
552+
updateHeightRateSetpoint(hgt_setpoint, target_climbrate, target_sinkrate, baro_altitude);
578553

579554
// Calculate the specific energy values required by the control loop
580555
_update_energy_estimates();

src/lib/tecs/TECS.hpp

Lines changed: 7 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,7 @@ class TECS
8484
void update_pitch_throttle(float pitch, float baro_altitude, float hgt_setpoint,
8585
float EAS_setpoint, float equivalent_airspeed, float eas_to_tas, bool climb_out_setpoint, float pitch_min_climbout,
8686
float throttle_min, float throttle_setpoint_max, float throttle_cruise,
87-
float pitch_limit_min, float pitch_limit_max);
87+
float pitch_limit_min, float pitch_limit_max, float target_climbrate, float target_sinkrate);
8888

8989
float get_throttle_setpoint() { return _last_throttle_setpoint; }
9090
float get_pitch_setpoint() { return _last_pitch_setpoint; }
@@ -138,7 +138,7 @@ class TECS
138138
uint64_t timestamp() { return _pitch_update_timestamp; }
139139
ECL_TECS_MODE tecs_mode() { return _tecs_mode; }
140140

141-
float hgt_setpoint_adj() { return _hgt_setpoint_adj; }
141+
float hgt_setpoint() { return _hgt_setpoint; }
142142
float vert_pos_state() { return _vert_pos_state; }
143143

144144
float TAS_setpoint_adj() { return _TAS_setpoint_adj; }
@@ -185,11 +185,7 @@ class TECS
185185
*/
186186
void handle_alt_step(float delta_alt, float altitude)
187187
{
188-
// add height reset delta to all variables involved
189-
// in filtering the demanded height
190-
_hgt_setpoint_in_prev += delta_alt;
191-
_hgt_setpoint_prev += delta_alt;
192-
_hgt_setpoint_adj_prev += delta_alt;
188+
_hgt_setpoint += delta_alt;
193189

194190
// reset height states
195191
_vert_pos_state = altitude;
@@ -254,10 +250,6 @@ class TECS
254250

255251
// height demand calculations
256252
float _hgt_setpoint{0.0f}; ///< demanded height tracked by the TECS algorithm (m)
257-
float _hgt_setpoint_in_prev{0.0f}; ///< previous value of _hgt_setpoint after noise filtering (m)
258-
float _hgt_setpoint_prev{0.0f}; ///< previous value of _hgt_setpoint after noise filtering and rate limiting (m)
259-
float _hgt_setpoint_adj{0.0f}; ///< demanded height used by the control loops after all filtering has been applied (m)
260-
float _hgt_setpoint_adj_prev{0.0f}; ///< value of _hgt_setpoint_adj from previous frame (m)
261253
float _hgt_rate_setpoint{0.0f}; ///< demanded climb rate tracked by the TECS algorithm
262254

263255
// vehicle physical limits
@@ -313,9 +305,11 @@ class TECS
313305
void _update_speed_setpoint();
314306

315307
/**
316-
* Update the desired height
308+
* Calculate desired height rate from altitude demand
317309
*/
318-
void _update_height_setpoint(float desired, float state);
310+
void updateHeightRateSetpoint(float alt_sp_amsl_m, float target_climbrate_m_s, float target_sinkrate_m_s,
311+
float alt_amsl);
312+
319313

320314
/**
321315
* Detect if the system is not capable of maintaining airspeed

src/modules/fw_pos_control_l1/FixedwingPositionControl.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -422,7 +422,7 @@ FixedwingPositionControl::tecs_status_publish()
422422
break;
423423
}
424424

425-
t.altitude_sp = _tecs.hgt_setpoint_adj();
425+
t.altitude_sp = _tecs.hgt_setpoint();
426426
t.altitude_filtered = _tecs.vert_pos_state();
427427

428428
t.true_airspeed_sp = _tecs.TAS_setpoint_adj();
@@ -2174,7 +2174,8 @@ FixedwingPositionControl::tecs_update_pitch_throttle(const hrt_abstime &now, flo
21742174
climbout_pitch_min_rad - radians(_param_fw_psp_off.get()),
21752175
throttle_min, throttle_max, throttle_cruise,
21762176
pitch_min_rad - radians(_param_fw_psp_off.get()),
2177-
pitch_max_rad - radians(_param_fw_psp_off.get()));
2177+
pitch_max_rad - radians(_param_fw_psp_off.get()),
2178+
_param_climbrate_target.get(), _param_sinkrate_target.get());
21782179

21792180
tecs_status_publish();
21802181
}

src/modules/fw_pos_control_l1/FixedwingPositionControl.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -423,6 +423,8 @@ class FixedwingPositionControl final : public ModuleBase<FixedwingPositionContro
423423
(ParamFloat<px4::params::FW_T_STE_R_TC>) _param_ste_rate_time_const,
424424
(ParamFloat<px4::params::FW_T_TAS_R_TC>) _param_tas_rate_time_const,
425425
(ParamFloat<px4::params::FW_T_SEB_R_FF>) _param_seb_rate_ff,
426+
(ParamFloat<px4::params::FW_T_CLIMB_R_SP>) _param_climbrate_target,
427+
(ParamFloat<px4::params::FW_T_SINK_R_SP>) _param_sinkrate_target,
426428

427429
(ParamFloat<px4::params::FW_THR_ALT_SCL>) _param_fw_thr_alt_scl,
428430
(ParamFloat<px4::params::FW_THR_CRUISE>) _param_fw_thr_cruise,

0 commit comments

Comments
 (0)