|
|
|
@ -366,7 +366,7 @@ void AP_TECS::_update_speed(float load_factor)
@@ -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,
@@ -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); |
|
|
|
|
} |
|
|
|
|