mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_TECS: added use_synthetic_airspeed() API
used by quadplane during transitions
This commit is contained in:
parent
eec491a1f9
commit
2fab15dcd5
@ -366,7 +366,7 @@ void AP_TECS::_update_speed(float load_factor)
|
||||
|
||||
// Get airspeed or default to halfway between min and max if
|
||||
// airspeed is not being used and set speed rate to zero
|
||||
if (!_ahrs.airspeed_sensor_enabled() || !_ahrs.airspeed_estimate(&_EAS)) {
|
||||
if (!(_use_synthetic_airspeed || _ahrs.airspeed_sensor_enabled()) || !_ahrs.airspeed_estimate(&_EAS)) {
|
||||
// If no airspeed available use average of min and max
|
||||
_EAS = 0.5f * (aparm.airspeed_min.get() + (float)aparm.airspeed_max.get());
|
||||
}
|
||||
@ -1034,9 +1034,14 @@ void AP_TECS::update_pitch_throttle(int32_t hgt_dem_cm,
|
||||
// Calculate specific energy quantitiues
|
||||
_update_energies();
|
||||
|
||||
// Calculate throttle demand - use simple pitch to throttle if no airspeed sensor
|
||||
if (_ahrs.airspeed_sensor_enabled()) {
|
||||
// Calculate throttle demand - use simple pitch to throttle if no
|
||||
// airspeed sensor.
|
||||
// Note that caller can demand the use of
|
||||
// synthetic airspeed for one loop if needed. This is required
|
||||
// during QuadPlane transition when pitch is constrained
|
||||
if (_ahrs.airspeed_sensor_enabled() || _use_synthetic_airspeed) {
|
||||
_update_throttle_with_airspeed();
|
||||
_use_synthetic_airspeed = false;
|
||||
} else {
|
||||
_update_throttle_without_airspeed(throttle_nudge);
|
||||
}
|
||||
|
@ -104,6 +104,11 @@ public:
|
||||
_pitch_max_limit = pitch_limit;
|
||||
}
|
||||
|
||||
// force use of synthetic airspeed for one loop
|
||||
void use_synthetic_airspeed(void) {
|
||||
_use_synthetic_airspeed = true;
|
||||
}
|
||||
|
||||
// this supports the TECS_* user settable parameters
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
@ -306,6 +311,9 @@ private:
|
||||
float SEB_delta;
|
||||
} logging;
|
||||
|
||||
// use synthetic airspeed for next loop
|
||||
bool _use_synthetic_airspeed;
|
||||
|
||||
// Update the airspeed internal state using a second order complementary filter
|
||||
void _update_speed(float load_factor);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user