APM:Libraries
location.cpp
Go to the documentation of this file.
1 /*
2  * location.cpp
3  * Copyright (C) Andrew Tridgell 2011
4  *
5  * This file is free software: you can redistribute it and/or modify it
6  * under the terms of the GNU General Public License as published by the
7  * Free Software Foundation, either version 3 of the License, or
8  * (at your option) any later version.
9  *
10  * This file is distributed in the hope that it will be useful, but
11  * WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13  * See the GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License along
16  * with this program. If not, see <http://www.gnu.org/licenses/>.
17  */
18 
19 /*
20  * this module deals with calculations involving struct Location
21  */
22 #include <AP_HAL/AP_HAL.h>
23 #include <stdlib.h>
24 #include "AP_Math.h"
25 #include "location.h"
26 
27 float longitude_scale(const struct Location &loc)
28 {
29  float scale = cosf(loc.lat * 1.0e-7f * DEG_TO_RAD);
30  return constrain_float(scale, 0.01f, 1.0f);
31 }
32 
33 
34 
35 // return distance in meters between two locations
36 float get_distance(const struct Location &loc1, const struct Location &loc2)
37 {
38  float dlat = (float)(loc2.lat - loc1.lat);
39  float dlong = ((float)(loc2.lng - loc1.lng)) * longitude_scale(loc2);
40  return norm(dlat, dlong) * LOCATION_SCALING_FACTOR;
41 }
42 
43 // return distance in centimeters to between two locations
44 uint32_t get_distance_cm(const struct Location &loc1, const struct Location &loc2)
45 {
46  return get_distance(loc1, loc2) * 100;
47 }
48 
49 // return horizontal distance between two positions in cm
50 float get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination)
51 {
52  return norm(destination.x-origin.x,destination.y-origin.y);
53 }
54 
55 // return bearing in centi-degrees between two locations
56 int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
57 {
58  int32_t off_x = loc2.lng - loc1.lng;
59  int32_t off_y = (loc2.lat - loc1.lat) / longitude_scale(loc2);
60  int32_t bearing = 9000 + atan2f(-off_y, off_x) * DEGX100;
61  if (bearing < 0) bearing += 36000;
62  return bearing;
63 }
64 
65 // return bearing in centi-degrees between two positions
66 float get_bearing_cd(const Vector3f &origin, const Vector3f &destination)
67 {
68  float bearing = atan2f(destination.y-origin.y, destination.x-origin.x) * DEGX100;
69  if (bearing < 0) {
70  bearing += 36000.0f;
71  }
72  return bearing;
73 }
74 
75 // see if location is past a line perpendicular to
76 // the line between point1 and point2. If point1 is
77 // our previous waypoint and point2 is our target waypoint
78 // then this function returns true if we have flown past
79 // the target waypoint
81  const struct Location &point1,
82  const struct Location &point2)
83 {
84  return location_path_proportion(location, point1, point2) >= 1.0f;
85 }
86 
87 
88 /*
89  return the proportion we are along the path from point1 to
90  point2, along a line parallel to point1<->point2.
91 
92  This will be less than >1 if we have passed point2
93  */
95  const struct Location &point1,
96  const struct Location &point2)
97 {
98  Vector2f vec1 = location_diff(point1, point2);
99  Vector2f vec2 = location_diff(point1, location);
100  float dsquared = sq(vec1.x) + sq(vec1.y);
101  if (dsquared < 0.001f) {
102  // the two points are very close together
103  return 1.0f;
104  }
105  return (vec1 * vec2) / dsquared;
106 }
107 
108 /*
109  * extrapolate latitude/longitude given bearing and distance
110  * Note that this function is accurate to about 1mm at a distance of
111  * 100m. This function has the advantage that it works in relative
112  * positions, so it keeps the accuracy even when dealing with small
113  * distances and floating point numbers
114  */
115 void location_update(struct Location &loc, float bearing, float distance)
116 {
117  float ofs_north = cosf(radians(bearing))*distance;
118  float ofs_east = sinf(radians(bearing))*distance;
119  location_offset(loc, ofs_north, ofs_east);
120 }
121 
122 /*
123  * extrapolate latitude/longitude given distances north and east
124  */
125 void location_offset(struct Location &loc, float ofs_north, float ofs_east)
126 {
127  if (!is_zero(ofs_north) || !is_zero(ofs_east)) {
128  int32_t dlat = ofs_north * LOCATION_SCALING_FACTOR_INV;
129  int32_t dlng = (ofs_east * LOCATION_SCALING_FACTOR_INV) / longitude_scale(loc);
130  loc.lat += dlat;
131  loc.lng += dlng;
132  }
133 }
134 
135 /*
136  return the distance in meters in North/East plane as a N/E vector
137  from loc1 to loc2
138  */
139 Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
140 {
141  return Vector2f((loc2.lat - loc1.lat) * LOCATION_SCALING_FACTOR,
142  (loc2.lng - loc1.lng) * LOCATION_SCALING_FACTOR * longitude_scale(loc1));
143 }
144 
145 /*
146  return the distance in meters in North/East/Down plane as a N/E/D vector
147  from loc1 to loc2
148  */
149 Vector3f location_3d_diff_NED(const struct Location &loc1, const struct Location &loc2)
150 {
151  return Vector3f((loc2.lat - loc1.lat) * LOCATION_SCALING_FACTOR,
152  (loc2.lng - loc1.lng) * LOCATION_SCALING_FACTOR * longitude_scale(loc1),
153  (loc1.alt - loc2.alt) * 0.01f);
154 }
155 
156 /*
157  return true if lat and lng match. Ignores altitude and options
158  */
159 bool locations_are_same(const struct Location &loc1, const struct Location &loc2) {
160  return (loc1.lat == loc2.lat) && (loc1.lng == loc2.lng);
161 }
162 
163 /*
164  * convert invalid waypoint with useful data. return true if location changed
165  */
166 bool location_sanitize(const struct Location &defaultLoc, struct Location &loc)
167 {
168  bool has_changed = false;
169  // convert lat/lng=0 to mean current point
170  if (loc.lat == 0 && loc.lng == 0) {
171  loc.lat = defaultLoc.lat;
172  loc.lng = defaultLoc.lng;
173  has_changed = true;
174  }
175 
176  // convert relative alt=0 to mean current alt
177  if (loc.alt == 0 && loc.flags.relative_alt) {
178  loc.flags.relative_alt = false;
179  loc.alt = defaultLoc.alt;
180  has_changed = true;
181  }
182 
183  // limit lat/lng to appropriate ranges
184  if (!check_latlng(loc)) {
185  loc.lat = defaultLoc.lat;
186  loc.lng = defaultLoc.lng;
187  has_changed = true;
188  }
189 
190  return has_changed;
191 }
192 
193 /*
194  print a int32_t lat/long in decimal degrees
195  */
196 void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon)
197 {
198  int32_t dec_portion, frac_portion;
199  int32_t abs_lat_or_lon = labs(lat_or_lon);
200 
201  // extract decimal portion (special handling of negative numbers to ensure we round towards zero)
202  dec_portion = abs_lat_or_lon / 10000000UL;
203 
204  // extract fractional portion
205  frac_portion = abs_lat_or_lon - dec_portion*10000000UL;
206 
207  // print output including the minus sign
208  if( lat_or_lon < 0 ) {
209  s->printf("-");
210  }
211  s->printf("%ld.%07ld",(long)dec_portion,(long)frac_portion);
212 }
213 
214 // return true when lat and lng are within range
215 bool check_lat(float lat)
216 {
217  return fabsf(lat) <= 90;
218 }
219 bool check_lng(float lng)
220 {
221  return fabsf(lng) <= 180;
222 }
223 bool check_lat(int32_t lat)
224 {
225  return labs(lat) <= 90*1e7;
226 }
227 bool check_lng(int32_t lng)
228 {
229  return labs(lng) <= 180*1e7;
230 }
231 bool check_latlng(float lat, float lng)
232 {
233  return check_lat(lat) && check_lng(lng);
234 }
235 bool check_latlng(int32_t lat, int32_t lng)
236 {
237  return check_lat(lat) && check_lng(lng);
238 }
240 {
241  return check_lat(loc.lat) && check_lng(loc.lng);
242 }
float norm(const T first, const U second, const Params... parameters)
Definition: AP_Math.h:190
#define LOCATION_SCALING_FACTOR
Definition: location.h:13
void location_update(struct Location &loc, float bearing, float distance)
Definition: location.cpp:115
Vector2< float > Vector2f
Definition: vector2.h:239
Vector3< float > Vector3f
Definition: vector3.h:246
float location_path_proportion(const struct Location &location, const struct Location &point1, const struct Location &point2)
Definition: location.cpp:94
float ofs_north
Definition: location.cpp:94
float get_distance(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:36
float ofs_east
Definition: location.cpp:94
float longitude_scale(const struct Location &loc)
Definition: location.cpp:27
bool check_lng(float lng)
Definition: location.cpp:219
void location_offset(struct Location &loc, float ofs_north, float ofs_east)
Definition: location.cpp:125
float distance
Definition: location.cpp:94
int32_t lat
param 3 - Latitude * 10**7
Definition: AP_Common.h:143
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:56
#define DEG_TO_RAD
Definition: definitions.h:30
uint32_t get_distance_cm(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:44
T y
Definition: vector2.h:37
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
Vector2f location_diff(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:139
float get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination)
Definition: location.cpp:50
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
Definition: AP_Common.h:142
bool is_zero(const T fVal1)
Definition: AP_Math.h:40
#define f(i)
T y
Definition: vector3.h:67
float bearing
Definition: location.cpp:94
bool check_latlng(float lat, float lng)
Definition: location.cpp:231
#define LOCATION_SCALING_FACTOR_INV
Definition: location.h:15
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
Definition: AP_Common.h:135
bool check_lat(float lat)
Definition: location.cpp:215
Vector2f location
Definition: location.cpp:16
float constrain_float(const float amt, const float low, const float high)
Definition: AP_Math.h:142
T x
Definition: vector2.h:37
int32_t lng
param 4 - Longitude * 10**7
Definition: AP_Common.h:144
Vector3f location_3d_diff_NED(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:149
static constexpr float radians(float deg)
Definition: AP_Math.h:158
#define DEGX100
Definition: definitions.h:34
float sq(const T val)
Definition: AP_Math.h:170
bool location_sanitize(const struct Location &defaultLoc, struct Location &loc)
Definition: location.cpp:166
bool location_passed_point(const struct Location &location, const struct Location &point1, const struct Location &point2)
Definition: location.cpp:80
void print_latlon(AP_HAL::BetterStream *s, int32_t lat_or_lon)
Definition: location.cpp:196
bool locations_are_same(const struct Location &loc1, const struct Location &loc2)
Definition: location.cpp:159
T x
Definition: vector3.h:67