43 if (
_ahrs !=
nullptr) {
48 offset(ekf_offset_neu.
x / 100.0f, ekf_offset_neu.
y / 100.0f);
119 if (desired_frame == frame) {
125 float alt_terr_cm = 0;
127 #if AP_TERRAIN_AVAILABLE 132 alt_terr_cm *= 100.0f;
154 alt_abs =
alt + ekf_origin.
alt;
158 alt_abs =
alt + alt_terr_cm;
166 switch (desired_frame) {
168 ret_alt_cm = alt_abs;
180 ret_alt_cm = alt_abs - ekf_origin.
alt;
184 ret_alt_cm = alt_abs - alt_terr_cm;
210 vec_neu.
x = vec_ne.
x;
211 vec_neu.
y = vec_ne.
y;
214 int32_t alt_above_origin_cm = 0;
218 vec_neu.
z = alt_above_origin_cm;
226 float dlat = (float)(loc2.
lat -
lat);
float norm(const T first, const U second, const Params... parameters)
#define LOCATION_SCALING_FACTOR
bool get_vector_from_origin_NEU(Vector3f &vec_neu) const
const struct Location & get_home(void) const
float longitude_scale(const struct Location &loc)
static AP_Terrain * _terrain
static const AP_AHRS_NavEKF * _ahrs
int32_t lat
param 3 - Latitude * 10**7
bool get_origin(Location &ret) const override
int32_t alt
param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M
ALT_FRAME get_alt_frame() const
bool get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
get altitude in desired frame
void offset(float ofs_north, float ofs_east)
#define LOCATION_SCALING_FACTOR_INV
Location_Class & operator=(const struct Location &loc)
bool change_alt_frame(ALT_FRAME desired_frame)
Location_Option_Flags flags
options bitmask (1<<0 = relative altitude)
bool get_vector_xy_from_origin_NE(Vector2f &vec_ne) const
void set_alt_cm(int32_t alt_cm, ALT_FRAME frame)
int32_t lng
param 4 - Longitude * 10**7
float get_distance(const struct Location &loc2) const
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)
ALT_FRAME
enumeration of possible altitude types
Location_Class()
constructors