AP_Avoidance: fixed use of fabs()

This commit is contained in:
Andrew Tridgell 2018-05-05 08:10:12 +10:00
parent 27442e4a7b
commit c4fafa490f
1 changed files with 2 additions and 2 deletions

View File

@ -312,9 +312,9 @@ float closest_approach_z(const Location &my_loc,
if (delta_pos_d >= 0 && delta_vel_d >= 0) {
ret = delta_pos_d;
} else if (delta_pos_d <= 0 && delta_vel_d <= 0) {
ret = fabs(delta_pos_d);
ret = fabsf(delta_pos_d);
} else {
ret = fabs(delta_pos_d - delta_vel_d * time_horizon);
ret = fabsf(delta_pos_d - delta_vel_d * time_horizon);
}
debug(" time_horizon: (%d)", time_horizon);