mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-24 15:40:31 +08:00
fix(tecs): use TAS trim for underspeed detection bounds
tas_error_bound was computed from equivalent_airspeed_trim (EAS) but subtracted from tas_min which is in TAS. At altitude where eas_to_tas > 1 the margin was proportionally too narrow, causing underspeed protection to engage later than intended. Add tas_trim = eas_to_tas * equivalent_airspeed_trim to TECSControl::Param, updated alongside tas_min/tas_max in initControlParams each cycle. Use it for the error bound so all underspeed threshold values are in TAS domain. Signed-off-by: Balduin <balduin@auterion.com>
This commit is contained in:
@@ -378,12 +378,12 @@ void TECSControl::_detectUnderspeed(const Input &input, const Param ¶m, cons
|
||||
|
||||
// this is the expected (something like standard) deviation from the airspeed setpoint that we allow the airspeed
|
||||
// to vary in before ramping in underspeed mitigation
|
||||
const float tas_error_bound = param.tas_error_percentage * param.equivalent_airspeed_trim;
|
||||
const float tas_error_bound = param.tas_error_percentage * param.tas_trim;
|
||||
|
||||
// this is the soft boundary where underspeed mitigation is ramped in
|
||||
// NOTE: it's currently the same as the error bound, but separated here to indicate these values do not in general
|
||||
// need to be the same
|
||||
const float tas_underspeed_soft_bound = param.tas_error_percentage * param.equivalent_airspeed_trim;
|
||||
const float tas_underspeed_soft_bound = param.tas_error_percentage * param.tas_trim;
|
||||
|
||||
const float tas_fully_undersped = math::max(param.tas_min - tas_error_bound - tas_underspeed_soft_bound, 0.0f);
|
||||
const float tas_starting_to_underspeed = math::max(param.tas_min - tas_error_bound, tas_fully_undersped);
|
||||
@@ -674,6 +674,7 @@ void TECS::initControlParams(float target_climbrate, float target_sinkrate, floa
|
||||
// Control
|
||||
_control_param.tas_min = eas_to_tas * _equivalent_airspeed_min;
|
||||
_control_param.tas_max = eas_to_tas * _equivalent_airspeed_max;
|
||||
_control_param.tas_trim = eas_to_tas * _control_param.equivalent_airspeed_trim;
|
||||
_control_param.pitch_max = pitch_limit_max;
|
||||
_control_param.pitch_min = pitch_limit_min;
|
||||
_control_param.throttle_trim = throttle_trim;
|
||||
|
||||
@@ -203,6 +203,7 @@ public:
|
||||
float max_climb_rate; ///< Climb rate produced by max allowed throttle [m/s].
|
||||
float vert_accel_limit; ///< Magnitude of the maximum vertical acceleration allowed [m/s²].
|
||||
float equivalent_airspeed_trim; ///< Equivalent cruise airspeed for airspeed less mode [m/s].
|
||||
float tas_trim; ///< True airspeed at trim (cruise) condition [m/s].
|
||||
float tas_min; ///< True airspeed demand lower limit [m/s].
|
||||
float tas_max; ///< True airspeed demand upper limit [m/s].
|
||||
float pitch_max; ///< Maximum pitch angle above trim allowed in [rad].
|
||||
@@ -730,6 +731,7 @@ private:
|
||||
.max_climb_rate = 5.0f,
|
||||
.vert_accel_limit = 0.0f,
|
||||
.equivalent_airspeed_trim = 15.0f,
|
||||
.tas_trim = 15.0f,
|
||||
.tas_min = 10.0f,
|
||||
.tas_max = 20.0f,
|
||||
.pitch_max = 0.5f,
|
||||
|
||||
Reference in New Issue
Block a user