APM:Libraries
Location.cpp
Go to the documentation of this file.
1 /*
2  * Location.cpp
3  */
4 
5 #include "Location.h"
6 
7 #include <AP_AHRS/AP_AHRS.h>
9 
10 extern const AP_HAL::HAL& hal;
11 
12 const AP_AHRS_NavEKF *Location_Class::_ahrs = nullptr;
13 AP_Terrain *Location_Class::_terrain = nullptr;
14 
17 {
18  zero();
19 }
20 
21 Location_Class::Location_Class(int32_t latitude, int32_t longitude, int32_t alt_in_cm, ALT_FRAME frame)
22 {
23  lat = latitude;
24  lng = longitude;
25  options = 0;
26  set_alt_cm(alt_in_cm, frame);
27 }
28 
30 {
31  lat = loc.lat;
32  lng = loc.lng;
33  alt = loc.alt;
34  options = loc.options;
35 }
36 
38 {
39  // store alt and alt frame
40  set_alt_cm(ekf_offset_neu.z, ALT_FRAME_ABOVE_ORIGIN);
41 
42  // calculate lat, lon
43  if (_ahrs != nullptr) {
45  if (_ahrs->get_origin(ekf_origin)) {
46  lat = ekf_origin.lat;
47  lng = ekf_origin.lng;
48  offset(ekf_offset_neu.x / 100.0f, ekf_offset_neu.y / 100.0f);
49  }
50  }
51 }
52 
54 {
55  lat = loc.lat;
56  lng = loc.lng;
57  alt = loc.alt;
58  options = loc.options;
59  return *this;
60 }
61 
62 void Location_Class::set_alt_cm(int32_t alt_cm, ALT_FRAME frame)
63 {
64  alt = alt_cm;
65  flags.relative_alt = false;
66  flags.terrain_alt = false;
67  flags.origin_alt = false;
68  switch (frame) {
69  case ALT_FRAME_ABSOLUTE:
70  // do nothing
71  break;
73  flags.relative_alt = true;
74  break;
76  flags.origin_alt = true;
77  break;
79  // we mark it as a relative altitude, as it doesn't have
80  // home alt added
81  flags.relative_alt = true;
82  flags.terrain_alt = true;
83  break;
84  }
85 }
86 
87 // converts altitude to new frame
89 {
90  int32_t new_alt_cm;
91  if (!get_alt_cm(desired_frame, new_alt_cm)) {
92  return false;
93  }
94  set_alt_cm(new_alt_cm, desired_frame);
95  return true;
96 }
97 
98 // get altitude frame
100 {
101  if (flags.terrain_alt) {
103  }
104  if (flags.origin_alt) {
105  return ALT_FRAME_ABOVE_ORIGIN;
106  }
107  if (flags.relative_alt) {
108  return ALT_FRAME_ABOVE_HOME;
109  }
110  return ALT_FRAME_ABSOLUTE;
111 }
112 
114 bool Location_Class::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
115 {
117 
118  // shortcut if desired and underlying frame are the same
119  if (desired_frame == frame) {
120  ret_alt_cm = alt;
121  return true;
122  }
123 
124  // check for terrain altitude
125  float alt_terr_cm = 0;
126  if (frame == ALT_FRAME_ABOVE_TERRAIN || desired_frame == ALT_FRAME_ABOVE_TERRAIN) {
127 #if AP_TERRAIN_AVAILABLE
128  if (_ahrs == nullptr || _terrain == nullptr || !_terrain->height_amsl(*(Location *)this, alt_terr_cm, true)) {
129  return false;
130  }
131  // convert terrain alt to cm
132  alt_terr_cm *= 100.0f;
133 #else
134  return false;
135 #endif
136  }
137 
138  // convert alt to absolute
139  int32_t alt_abs;
140  switch (frame) {
141  case ALT_FRAME_ABSOLUTE:
142  alt_abs = alt;
143  break;
145  alt_abs = alt + _ahrs->get_home().alt;
146  break;
148  {
149  // fail if we cannot get ekf origin
151  if (_ahrs == nullptr || !_ahrs->get_origin(ekf_origin)) {
152  return false;
153  }
154  alt_abs = alt + ekf_origin.alt;
155  }
156  break;
158  alt_abs = alt + alt_terr_cm;
159  break;
160  default:
161  // unknown conversion to absolute alt, this should never happen
162  return false;
163  }
164 
165  // convert absolute to desired frame
166  switch (desired_frame) {
167  case ALT_FRAME_ABSOLUTE:
168  ret_alt_cm = alt_abs;
169  return true;
171  ret_alt_cm = alt_abs - _ahrs->get_home().alt;
172  return true;
174  {
175  // fail if we cannot get ekf origin
177  if (_ahrs == nullptr || !_ahrs->get_origin(ekf_origin)) {
178  return false;
179  }
180  ret_alt_cm = alt_abs - ekf_origin.alt;
181  return true;
182  }
184  ret_alt_cm = alt_abs - alt_terr_cm;
185  return true;
186  default:
187  // should never happen
188  return false;
189  }
190 }
191 
193 {
195  if (!_ahrs->get_origin(ekf_origin)) {
196  return false;
197  }
198  vec_ne.x = (lat-ekf_origin.lat) * LATLON_TO_CM;
199  vec_ne.y = (lng-ekf_origin.lng) * LATLON_TO_CM * longitude_scale(ekf_origin);
200  return true;
201 }
202 
204 {
205  // convert lat, lon
206  Vector2f vec_ne;
207  if (!get_vector_xy_from_origin_NE(vec_ne)) {
208  return false;
209  }
210  vec_neu.x = vec_ne.x;
211  vec_neu.y = vec_ne.y;
212 
213  // convert altitude
214  int32_t alt_above_origin_cm = 0;
215  if (!get_alt_cm(ALT_FRAME_ABOVE_ORIGIN, alt_above_origin_cm)) {
216  return false;
217  }
218  vec_neu.z = alt_above_origin_cm;
219 
220  return true;
221 }
222 
223 // return distance in meters between two locations
224 float Location_Class::get_distance(const struct Location &loc2) const
225 {
226  float dlat = (float)(loc2.lat - lat);
227  float dlng = ((float)(loc2.lng - lng)) * longitude_scale(loc2);
228  return norm(dlat, dlng) * LOCATION_SCALING_FACTOR;
229 }
230 
231 // extrapolate latitude/longitude given distances (in meters) north and east
233 {
234  // use is_equal() because is_zero() is a local class conflict and is_zero() in AP_Math does not belong to a class
235  if (!is_equal(ofs_north, 0.0f) || !is_equal(ofs_east, 0.0f)) {
236  int32_t dlat = ofs_north * LOCATION_SCALING_FACTOR_INV;
237  int32_t dlng = (ofs_east * LOCATION_SCALING_FACTOR_INV) / longitude_scale(*this);
238  lat += dlat;
239  lng += dlng;
240  }
241 }
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
#define LOCATION_SCALING_FACTOR
Definition: location.h:13
bool get_vector_from_origin_NEU(Vector3f &vec_neu) const
Definition: Location.cpp:203
float ofs_north
Definition: location.cpp:94
const struct Location & get_home(void) const
Definition: AP_AHRS.h:435
float ofs_east
Definition: location.cpp:94
float longitude_scale(const struct Location &loc)
Definition: location.cpp:27
static AP_Terrain * _terrain
Definition: Location.h:77
static const AP_AHRS_NavEKF * _ahrs
Definition: Location.h:76
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
bool get_origin(Location &ret) const override
T y
Definition: vector2.h:37
void zero(void)
Definition: Location.h:73
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
ALT_FRAME get_alt_frame() const
Definition: Location.cpp:99
bool get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
get altitude in desired frame
Definition: Location.cpp:114
#define f(i)
T y
Definition: vector3.h:67
T z
Definition: vector3.h:67
void offset(float ofs_north, float ofs_east)
Definition: Location.cpp:232
#define LOCATION_SCALING_FACTOR_INV
Definition: location.h:15
Location_Class & operator=(const struct Location &loc)
Definition: Location.cpp:53
bool change_alt_frame(ALT_FRAME desired_frame)
Definition: Location.cpp:88
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Definition: AP_Common.h:135
T x
Definition: vector2.h:37
bool get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
Definition: Location.cpp:192
void set_alt_cm(int32_t alt_cm, ALT_FRAME frame)
Definition: Location.cpp:62
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
float get_distance(const struct Location &loc2) const
Definition: Location.cpp:224
std::enable_if< std::is_integral< typename std::common_type< Arithmetic1, Arithmetic2 >::type >::value,bool >::type is_equal(const Arithmetic1 v_1, const Arithmetic2 v_2)
Definition: AP_Math.cpp:12
#define LATLON_TO_CM
Definition: definitions.h:55
ALT_FRAME
enumeration of possible altitude types
Definition: Location.h:22
Location_Class()
constructors
Definition: Location.cpp:16
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
T x
Definition: vector3.h:67
uint8_t options
Definition: AP_Common.h:136