diff --git a/libraries/AP_Declination/AP_Declination.cpp b/libraries/AP_Declination/AP_Declination.cpp index 550312000e..5ff2fce6df 100644 --- a/libraries/AP_Declination/AP_Declination.cpp +++ b/libraries/AP_Declination/AP_Declination.cpp @@ -36,9 +36,10 @@ bool AP_Declination::get_mag_field_ef(float latitude_deg, float longitude_deg, f { bool valid_input_data = true; - /* round down to nearest sampling resolution */ - int32_t min_lat = static_cast(static_cast(floorf(latitude_deg / SAMPLING_RES)) * SAMPLING_RES); - int32_t min_lon = static_cast(static_cast(floorf(longitude_deg / SAMPLING_RES)) * SAMPLING_RES); + /* round down to nearest sampling resolution. On some platforms (e.g. clang on macOS), + the behaviour of implicit casts from int32 to float can be undefined thus making it explicit here. */ + float min_lat = float(static_cast(static_cast(floorf(latitude_deg / SAMPLING_RES)) * SAMPLING_RES)); + float min_lon = float(static_cast(static_cast(floorf(longitude_deg / SAMPLING_RES)) * SAMPLING_RES)); /* for the rare case of hitting the bounds exactly * the rounding logic wouldn't fit, so enforce it. @@ -46,22 +47,22 @@ bool AP_Declination::get_mag_field_ef(float latitude_deg, float longitude_deg, f /* limit to table bounds - required for maxima even when table spans full globe range */ if (latitude_deg <= SAMPLING_MIN_LAT) { - min_lat = static_cast(SAMPLING_MIN_LAT); + min_lat = float(static_cast(SAMPLING_MIN_LAT)); valid_input_data = false; } if (latitude_deg >= SAMPLING_MAX_LAT) { - min_lat = static_cast(static_cast(latitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES); + min_lat = float(static_cast(static_cast(latitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES)); valid_input_data = false; } if (longitude_deg <= SAMPLING_MIN_LON) { - min_lon = static_cast(SAMPLING_MIN_LON); + min_lon = float(static_cast(SAMPLING_MIN_LON)); valid_input_data = false; } if (longitude_deg >= SAMPLING_MAX_LON) { - min_lon = static_cast(static_cast(longitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES); + min_lon = float(static_cast(static_cast(longitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES)); valid_input_data = false; }