APM:Libraries
Location.h
Go to the documentation of this file.
1 /*
2  * Location.h
3  *
4  */
5 
6 
7 #ifndef LOCATION_H
8 #define LOCATION_H
9 
10 #include <AP_Common/AP_Common.h>
11 #include <AP_Math/AP_Math.h>
12 #include <AP_HAL/AP_HAL.h>
13 
14 class AP_AHRS_NavEKF;
15 class AP_Terrain;
16 
17 class Location_Class : public Location
18 {
19 public:
20 
22  enum ALT_FRAME {
27  };
28 
31  Location_Class(int32_t latitude, int32_t longitude, int32_t alt_in_cm, ALT_FRAME frame);
32  Location_Class(const Location& loc);
33  Location_Class(const Vector3f &ekf_offset_neu);
34 
36  static void set_ahrs(const AP_AHRS_NavEKF* ahrs) { _ahrs = ahrs; }
37  static void set_terrain(AP_Terrain* terrain) { _terrain = terrain; }
38 
39  // operators
40  Location_Class& operator=(const struct Location &loc);
41 
42  // set altitude
43  void set_alt_cm(int32_t alt_cm, ALT_FRAME frame);
44 
45  // get altitude (in cm) in the desired frame
46  // returns false on failure to get altitude in the desired frame which
47  // can only happen if the original frame or desired frame is above-terrain
48  bool get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const;
49 
50  // get altitude frame
51  ALT_FRAME get_alt_frame() const;
52 
53  // converts altitude to new frame
54  // returns false on failure to convert which can only happen if
55  // the original frame or desired frame is above-terrain
56  bool change_alt_frame(ALT_FRAME desired_frame);
57 
58  // get position as a vector from origin (x,y only or x,y,z)
59  // return false on failure to get the vector which can only
60  // happen if the EKF origin has not been set yet
61  // x, y and z are in centimetres
62  bool get_vector_xy_from_origin_NE(Vector2f &vec_ne) const;
63  bool get_vector_from_origin_NEU(Vector3f &vec_neu) const;
64 
65  // return distance in meters between two locations
66  float get_distance(const struct Location &loc2) const;
67 
68  // extrapolate latitude/longitude given distances (in meters) north and east
69  void offset(float ofs_north, float ofs_east);
70 
71  bool is_zero(void) { return (lat == 0 && lng == 0 && alt == 0 && options == 0); }
72 
73  void zero(void) { lat = lng = alt = 0; options = 0; }
74 
75 private:
76  static const AP_AHRS_NavEKF *_ahrs;
77  static AP_Terrain *_terrain;
78 };
79 
80 #endif /* LOCATION_H */
bool get_vector_from_origin_NEU(Vector3f &vec_neu) const
Definition: Location.cpp:203
AP_AHRS_NavEKF & ahrs
Definition: AHRS_Test.cpp:39
float ofs_north
Definition: location.cpp:94
float ofs_east
Definition: location.cpp:94
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
static void set_terrain(AP_Terrain *terrain)
Definition: Location.h:37
static void set_ahrs(const AP_AHRS_NavEKF *ahrs)
accept reference to ahrs and (indirectly) EKF
Definition: Location.h:36
bool is_zero(void)
Definition: Location.h:71
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
void offset(float ofs_north, float ofs_east)
Definition: Location.cpp:232
Location_Class & operator=(const struct Location &loc)
Definition: Location.cpp:53
bool change_alt_frame(ALT_FRAME desired_frame)
Definition: Location.cpp:88
Common definitions and utility routines for the ArduPilot libraries.
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
ALT_FRAME
enumeration of possible altitude types
Definition: Location.h:22
Location_Class()
constructors
Definition: Location.cpp:16
uint8_t options
Definition: AP_Common.h:136