|
|
|
@ -37,8 +37,8 @@ bool AP_Declination::get_mag_field_ef(float latitude_deg, float longitude_deg, f
@@ -37,8 +37,8 @@ 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<int32_t>(static_cast<int32_t>(latitude_deg / SAMPLING_RES) * SAMPLING_RES); |
|
|
|
|
int32_t min_lon = static_cast<int32_t>(static_cast<int32_t>(longitude_deg / SAMPLING_RES) * SAMPLING_RES); |
|
|
|
|
int32_t min_lat = static_cast<int32_t>(static_cast<int32_t>(floorf(latitude_deg / SAMPLING_RES)) * SAMPLING_RES); |
|
|
|
|
int32_t min_lon = static_cast<int32_t>(static_cast<int32_t>(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. |
|
|
|
|