mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_TECS: Don't fetch the land slewrate if it's not needed
Co-authored-by: WickedShell <Wicked.Shell.Scripts@gmail.com>
This commit is contained in:
parent
bbe01adc7e
commit
8ae34a1977
@ -700,10 +700,11 @@ void AP_TECS::_update_throttle_with_airspeed(void)
|
||||
// Rate limit PD + FF throttle
|
||||
// Calculate the throttle increment from the specified slew time
|
||||
int8_t throttle_slewrate = aparm.throttle_slewrate;
|
||||
int8_t land_slewrate = _landing.get_throttle_slewrate();
|
||||
|
||||
if (_landing.is_on_approach() && land_slewrate >0) {
|
||||
throttle_slewrate = land_slewrate;
|
||||
if (_landing.is_on_approach()) {
|
||||
const int8_t land_slewrate = _landing.get_throttle_slewrate();
|
||||
if (land_slewrate > 0) {
|
||||
throttle_slewrate = land_slewrate;
|
||||
}
|
||||
}
|
||||
|
||||
if (throttle_slewrate != 0) {
|
||||
|
Loading…
Reference in New Issue
Block a user