Copter: correct abs vs fabsf usage in Attitude

This commit is contained in:
Peter Barker 2019-09-11 16:13:35 +10:00 committed by Andrew Tridgell
parent 506126cb44
commit 458f106c9b
1 changed files with 2 additions and 1 deletions

View File

@ -56,7 +56,8 @@ void Copter::update_throttle_hover()
float throttle = motors->get_throttle();
// calc average throttle if we are in a level hover
if (throttle > 0.0f && abs(inertial_nav.get_velocity_z()) < 60 && labs(ahrs.roll_sensor) < 500 && labs(ahrs.pitch_sensor) < 500) {
if (throttle > 0.0f && fabsf(inertial_nav.get_velocity_z()) < 60 &&
labs(ahrs.roll_sensor) < 500 && labs(ahrs.pitch_sensor) < 500) {
// Can we set the time constant automatically
motors->update_throttle_hover(0.01f);
}