CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_Common/Location.h
Views: 1798
1
#pragma once
2
3
#include <AP_Math/AP_Math.h>
4
5
#define LOCATION_ALT_MAX_M 83000 // maximum altitude (in meters) that can be fit into Location structure's alt field
6
7
class Location
8
{
9
public:
10
11
uint8_t relative_alt : 1; // 1 if altitude is relative to home
12
uint8_t loiter_ccw : 1; // 0 if clockwise, 1 if counter clockwise
13
uint8_t terrain_alt : 1; // this altitude is above terrain
14
uint8_t origin_alt : 1; // this altitude is above ekf origin
15
uint8_t loiter_xtrack : 1; // 0 to crosstrack from center of waypoint, 1 to crosstrack from tangent exit location
16
17
// note that mission storage only stores 24 bits of altitude (~ +/- 83km)
18
int32_t alt; // in cm
19
int32_t lat; // in 1E7 degrees
20
int32_t lng; // in 1E7 degrees
21
22
/// enumeration of possible altitude types
23
enum class AltFrame {
24
ABSOLUTE = 0,
25
ABOVE_HOME = 1,
26
ABOVE_ORIGIN = 2,
27
ABOVE_TERRAIN = 3
28
};
29
30
/// constructors
31
Location() { zero(); }
32
Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, AltFrame frame);
33
Location(const Vector3f &ekf_offset_neu, AltFrame frame);
34
Location(const Vector3d &ekf_offset_neu, AltFrame frame);
35
36
// set altitude
37
void set_alt_cm(int32_t alt_cm, AltFrame frame);
38
// set_alt_m - set altitude in metres
39
void set_alt_m(float alt_m, AltFrame frame) {
40
set_alt_cm(alt_m*100, frame);
41
}
42
43
// get altitude (in cm) in the desired frame
44
// returns false on failure to get altitude in the desired frame which can only happen if the original frame or desired frame is:
45
// - above-terrain and the terrain database can't supply terrain height amsl
46
// - above-home and home is not set
47
// - above-origin and origin is not set
48
bool get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const WARN_IF_UNUSED;
49
// same as get_alt_cm but in metres:
50
bool get_alt_m(AltFrame desired_frame, float &ret_alt) const WARN_IF_UNUSED;
51
52
// get altitude frame
53
AltFrame get_alt_frame() const;
54
55
// converts altitude to new frame
56
// returns false on failure to convert which can only happen if the original frame or desired frame is:
57
// - above-terrain and the terrain database can't supply terrain height amsl
58
// - above-home and home is not set
59
// - above-origin and origin is not set
60
bool change_alt_frame(AltFrame desired_frame);
61
62
// get position as a vector (in cm) from origin (x,y only or
63
// x,y,z) return false on failure to get the vector which can only
64
// happen if the EKF origin has not been set yet x, y and z are in
65
// centimetres. If this method returns false then vec_ne is
66
// unmodified.
67
template<typename T>
68
bool get_vector_xy_from_origin_NE(T &vec_ne) const WARN_IF_UNUSED;
69
// converts location to a vector from origin; if this method returns
70
// false then vec_neu is unmodified
71
template<typename T>
72
bool get_vector_from_origin_NEU(T &vec_neu) const WARN_IF_UNUSED;
73
74
// return horizontal distance in meters between two locations
75
ftype get_distance(const Location &loc2) const;
76
77
// return the altitude difference in meters taking into account alt frame.
78
bool get_alt_distance(const Location &loc2, ftype &distance) const WARN_IF_UNUSED;
79
80
// return the distance in meters in North/East/Down plane as a N/E/D vector to loc2
81
// NOT CONSIDERING ALT FRAME!
82
Vector3f get_distance_NED(const Location &loc2) const;
83
Vector3d get_distance_NED_double(const Location &loc2) const;
84
85
// return the distance in meters in North/East/Down plane as a N/E/D vector to loc2 considering alt frame, if altitude cannot be resolved down distance is 0
86
Vector3f get_distance_NED_alt_frame(const Location &loc2) const;
87
88
// return the distance in meters in North/East plane as a N/E vector to loc2
89
Vector2f get_distance_NE(const Location &loc2) const;
90
Vector2d get_distance_NE_double(const Location &loc2) const;
91
Vector2F get_distance_NE_ftype(const Location &loc2) const;
92
93
// extrapolate latitude/longitude given distances (in meters) north and east
94
static void offset_latlng(int32_t &lat, int32_t &lng, ftype ofs_north, ftype ofs_east);
95
void offset(ftype ofs_north, ftype ofs_east);
96
// extrapolate latitude/longitude given distances (in meters) north
97
// and east. Note that this is metres, *even for the altitude*.
98
void offset(const Vector3p &ofs_ned);
99
100
// extrapolate latitude/longitude given bearing and distance
101
void offset_bearing(ftype bearing_deg, ftype distance);
102
103
// extrapolate latitude/longitude given bearing, pitch and distance
104
void offset_bearing_and_pitch(ftype bearing_deg, ftype pitch_deg, ftype distance);
105
106
// longitude_scale - returns the scaler to compensate for
107
// shrinking longitude as you move north or south from the equator
108
// Note: this does not include the scaling to convert
109
// longitude/latitude points to meters or centimeters
110
static ftype longitude_scale(int32_t lat);
111
112
bool is_zero(void) const WARN_IF_UNUSED;
113
114
void zero(void);
115
116
// return the bearing in radians, from 0 to 2*Pi
117
ftype get_bearing(const Location &loc2) const;
118
119
// return bearing in centi-degrees from location to loc2, return is 0 to 35999
120
int32_t get_bearing_to(const Location &loc2) const {
121
return int32_t(get_bearing(loc2) * DEGX100 + 0.5);
122
}
123
124
// check if lat and lng match. Ignore altitude and options
125
bool same_latlon_as(const Location &loc2) const;
126
127
// check if altitude matches.
128
bool same_alt_as(const Location &loc2) const;
129
130
// check if lat, lng, and alt match.
131
bool same_loc_as(const Location &loc2) const {
132
return same_latlon_as(loc2) && same_alt_as(loc2);
133
}
134
135
/*
136
* convert invalid waypoint with useful data. return true if location changed
137
*/
138
bool sanitize(const Location &defaultLoc);
139
140
// return true when lat and lng are within range
141
bool check_latlng() const;
142
143
// see if location is past a line perpendicular to
144
// the line between point1 and point2 and passing through point2.
145
// If point1 is our previous waypoint and point2 is our target waypoint
146
// then this function returns true if we have flown past
147
// the target waypoint
148
bool past_interval_finish_line(const Location &point1, const Location &point2) const;
149
150
/*
151
return the proportion we are along the path from point1 to
152
point2, along a line parallel to point1<->point2.
153
This will be more than 1 if we have passed point2
154
*/
155
float line_path_proportion(const Location &point1, const Location &point2) const;
156
157
// update altitude and alt-frame base on this location's horizontal position between point1 and point2
158
// this location's lat,lon is used to calculate the alt of the closest point on the line between point1 and point2
159
// origin and destination's altitude frames must be the same
160
// this alt-frame will be updated to match the destination alt frame
161
void linearly_interpolate_alt(const Location &point1, const Location &point2);
162
163
bool initialised() const { return (lat !=0 || lng != 0 || alt != 0); }
164
165
// wrap longitude at -180e7 to 180e7
166
static int32_t wrap_longitude(int64_t lon);
167
168
// limit latitude to -90e7 to 90e7
169
static int32_t limit_lattitude(int32_t lat);
170
171
// get lon1-lon2, wrapping at -180e7 to 180e7
172
static int32_t diff_longitude(int32_t lon1, int32_t lon2);
173
174
private:
175
176
// scaling factor from 1e-7 degrees to meters at equator
177
// == 1.0e-7 * DEG_TO_RAD * RADIUS_OF_EARTH
178
static constexpr float LOCATION_SCALING_FACTOR = LATLON_TO_M;
179
// inverse of LOCATION_SCALING_FACTOR
180
static constexpr float LOCATION_SCALING_FACTOR_INV = LATLON_TO_M_INV;
181
};
182
183