AP_GPS: change isnanf for isnan

This commit is contained in:
Pierre Kancir 2023-02-26 23:08:21 +01:00 committed by Tom Pittenger
parent ca6a804f28
commit 8d962f915e
1 changed files with 1 additions and 1 deletions

View File

@ -379,7 +379,7 @@ void AP_GPS_UAVCAN::handle_velocity(const float vx, const float vy, const float
interim_state.velocity = vel;
velocity_to_speed_course(interim_state);
// assume we have vertical velocity if we ever get a non-zero Z velocity
if (!isnanf(vel.z) && !is_zero(vel.z)) {
if (!isnan(vel.z) && !is_zero(vel.z)) {
interim_state.have_vertical_velocity = true;
} else {
interim_state.have_vertical_velocity = state.have_vertical_velocity;