mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_TECS: Remove useless 'if' statement
This should fix CID 91386. Before removing the 'if', I checked the log to confirm that both branch didn't end-up being equal by mistake in some commit. But it looks like the file was added in the project this way.
This commit is contained in:
parent
c6edae7e8e
commit
d8b58690ad
@ -406,18 +406,8 @@ void AP_TECS::_update_speed_demand(void)
|
||||
// calculate velocity rate limits based on physical performance limits
|
||||
// provision to use a different rate limit if bad descent or underspeed condition exists
|
||||
// Use 50% of maximum energy rate to allow margin for total energy contgroller
|
||||
float velRateMax;
|
||||
float velRateMin;
|
||||
if ((_flags.badDescent) || (_flags.underspeed))
|
||||
{
|
||||
velRateMax = 0.5f * _STEdot_max / _TAS_state;
|
||||
velRateMin = 0.5f * _STEdot_min / _TAS_state;
|
||||
}
|
||||
else
|
||||
{
|
||||
velRateMax = 0.5f * _STEdot_max / _TAS_state;
|
||||
velRateMin = 0.5f * _STEdot_min / _TAS_state;
|
||||
}
|
||||
float velRateMax = 0.5f * _STEdot_max / _TAS_state;
|
||||
float velRateMin = 0.5f * _STEdot_min / _TAS_state;
|
||||
|
||||
// Apply rate limit
|
||||
if ((_TAS_dem - _TAS_dem_adj) > (velRateMax * 0.1f))
|
||||
|
Loading…
Reference in New Issue
Block a user