APM:Libraries
AP_Declination.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * Adam M Rivera
18  * With direction from: Andrew Tridgell, Jason Short, Justin Beech
19  *
20  * Adapted from: http://www.societyofrobots.com/robotforum/index.php?topic=11855.0
21  * Scott Ferguson
22  * scottfromscott@gmail.com
23  *
24  */
25 #include "AP_Declination.h"
26 
27 #include <cmath>
28 
29 #include <AP_Common/AP_Common.h>
30 #include <AP_Math/AP_Math.h>
31 
32 /*
33  calculate magnetic field intensity and orientation
34 */
35 bool AP_Declination::get_mag_field_ef(float latitude_deg, float longitude_deg, float &intensity_gauss, float &declination_deg, float &inclination_deg)
36 {
37  bool valid_input_data = true;
38 
39  /* round down to nearest sampling resolution */
40  int32_t min_lat = static_cast<int32_t>(static_cast<int32_t>(latitude_deg / SAMPLING_RES) * SAMPLING_RES);
41  int32_t min_lon = static_cast<int32_t>(static_cast<int32_t>(longitude_deg / SAMPLING_RES) * SAMPLING_RES);
42 
43  /* for the rare case of hitting the bounds exactly
44  * the rounding logic wouldn't fit, so enforce it.
45  */
46 
47  /* limit to table bounds - required for maxima even when table spans full globe range */
48  if (latitude_deg <= SAMPLING_MIN_LAT) {
49  min_lat = static_cast<int32_t>(SAMPLING_MIN_LAT);
50  valid_input_data = false;
51  }
52 
53  if (latitude_deg >= SAMPLING_MAX_LAT) {
54  min_lat = static_cast<int32_t>(static_cast<int32_t>(latitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES);
55  valid_input_data = false;
56  }
57 
58  if (longitude_deg <= SAMPLING_MIN_LON) {
59  min_lon = static_cast<int32_t>(SAMPLING_MIN_LON);
60  valid_input_data = false;
61  }
62 
63  if (longitude_deg >= SAMPLING_MAX_LON) {
64  min_lon = static_cast<int32_t>(static_cast<int32_t>(longitude_deg / SAMPLING_RES) * SAMPLING_RES - SAMPLING_RES);
65  valid_input_data = false;
66  }
67 
68  /* find index of nearest low sampling point */
69  uint32_t min_lat_index = static_cast<uint32_t>((-(SAMPLING_MIN_LAT) + min_lat) / SAMPLING_RES);
70  uint32_t min_lon_index = static_cast<uint32_t>((-(SAMPLING_MIN_LON) + min_lon) / SAMPLING_RES);
71 
72  /* calculate intensity */
73 
74  float data_sw = intensity_table[min_lat_index][min_lon_index];
75  float data_se = intensity_table[min_lat_index][min_lon_index + 1];;
76  float data_ne = intensity_table[min_lat_index + 1][min_lon_index + 1];
77  float data_nw = intensity_table[min_lat_index + 1][min_lon_index];
78 
79  /* perform bilinear interpolation on the four grid corners */
80 
81  float data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw;
82  float data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw;
83 
84  intensity_gauss = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min;
85 
86  /* calculate declination */
87 
88  data_sw = declination_table[min_lat_index][min_lon_index];
89  data_se = declination_table[min_lat_index][min_lon_index + 1];;
90  data_ne = declination_table[min_lat_index + 1][min_lon_index + 1];
91  data_nw = declination_table[min_lat_index + 1][min_lon_index];
92 
93  /* perform bilinear interpolation on the four grid corners */
94 
95  data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw;
96  data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw;
97 
98  declination_deg = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min;
99 
100  /* calculate inclination */
101 
102  data_sw = inclination_table[min_lat_index][min_lon_index];
103  data_se = inclination_table[min_lat_index][min_lon_index + 1];;
104  data_ne = inclination_table[min_lat_index + 1][min_lon_index + 1];
105  data_nw = inclination_table[min_lat_index + 1][min_lon_index];
106 
107  /* perform bilinear interpolation on the four grid corners */
108 
109  data_min = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_se - data_sw) + data_sw;
110  data_max = ((longitude_deg - min_lon) / SAMPLING_RES) * (data_ne - data_nw) + data_nw;
111 
112  inclination_deg = ((latitude_deg - min_lat) / SAMPLING_RES) * (data_max - data_min) + data_min;
113 
114  return valid_input_data;
115 }
116 
117 
118 /*
119  calculate magnetic field intensity and orientation
120 */
121 float AP_Declination::get_declination(float latitude_deg, float longitude_deg)
122 {
123  float declination_deg=0, inclination_deg=0, intensity_gauss=0;
124 
125  get_mag_field_ef(latitude_deg, longitude_deg, intensity_gauss, declination_deg, inclination_deg);
126 
127  return declination_deg;
128 }
129 
static const float inclination_table[19][37]
static const float SAMPLING_MAX_LAT
static const float SAMPLING_MAX_LON
static const float SAMPLING_MIN_LAT
static const float SAMPLING_RES
static const float intensity_table[19][37]
Common definitions and utility routines for the ArduPilot libraries.
static float get_declination(float latitude_deg, float longitude_deg)
static bool get_mag_field_ef(float latitude_deg, float longitude_deg, float &intensity_gauss, float &declination_deg, float &inclination_deg)
static const float SAMPLING_MIN_LON
static const float declination_table[19][37]