123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145 |
- #include "AP_Declination.h"
- #include <cmath>
- #include <AP_Common/AP_Common.h>
- #include <AP_Math/AP_Math.h>
- bool AP_Declination::get_mag_field_ef(float latitude_deg, float longitude_deg, float &intensity_gauss, float &declination_deg, float &inclination_deg)
- {
- bool valid_input_data = true;
-
- 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);
-
-
- if (latitude_deg <= SAMPLING_MIN_LAT) {
- min_lat = static_cast<int32_t>(SAMPLING_MIN_LAT);
- valid_input_data = false;
- }
- if (latitude_deg >= SAMPLING_MAX_LAT) {
- min_lat = static_cast<int32_t>(static_cast<int32_t>(latitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES);
- valid_input_data = false;
- }
- if (longitude_deg <= SAMPLING_MIN_LON) {
- min_lon = static_cast<int32_t>(SAMPLING_MIN_LON);
- valid_input_data = false;
- }
- if (longitude_deg >= SAMPLING_MAX_LON) {
- min_lon = static_cast<int32_t>(static_cast<int32_t>(longitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES);
- valid_input_data = false;
- }
-
- uint32_t min_lat_index = static_cast<uint32_t>((-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES);
- uint32_t min_lon_index = static_cast<uint32_t>((-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES);
-
- float data_sw = intensity_table[min_lat_index][min_lon_index];
- float data_se = intensity_table[min_lat_index][min_lon_index + 1];;
- float data_ne = intensity_table[min_lat_index + 1][min_lon_index + 1];
- float data_nw = intensity_table[min_lat_index + 1][min_lon_index];
-
- float data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw;
- float data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw;
- intensity_gauss = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min;
-
- data_sw = declination_table[min_lat_index][min_lon_index];
- data_se = declination_table[min_lat_index][min_lon_index + 1];;
- data_ne = declination_table[min_lat_index + 1][min_lon_index + 1];
- data_nw = declination_table[min_lat_index + 1][min_lon_index];
-
- data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw;
- data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw;
- declination_deg = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min;
-
- data_sw = inclination_table[min_lat_index][min_lon_index];
- data_se = inclination_table[min_lat_index][min_lon_index + 1];;
- data_ne = inclination_table[min_lat_index + 1][min_lon_index + 1];
- data_nw = inclination_table[min_lat_index + 1][min_lon_index];
-
- data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw;
- data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw;
- inclination_deg = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min;
- return valid_input_data;
- }
- float AP_Declination::get_declination(float latitude_deg, float longitude_deg)
- {
- float declination_deg=0, inclination_deg=0, intensity_gauss=0;
- get_mag_field_ef(latitude_deg, longitude_deg, intensity_gauss, declination_deg, inclination_deg);
- return declination_deg;
- }
- Vector3f AP_Declination::get_earth_field_ga(const Location &loc)
- {
- float declination_deg=0, inclination_deg=0, intensity_gauss=0;
- get_mag_field_ef(loc.lat*1.0e-7f, loc.lng*1.0e-7f, intensity_gauss, declination_deg, inclination_deg);
-
- Vector3f mag_ef = Vector3f(intensity_gauss, 0.0, 0.0);
- Matrix3f R;
- R.from_euler(0.0f, -ToRad(inclination_deg), ToRad(declination_deg));
- mag_ef = R * mag_ef;
- return mag_ef;
- }
|