Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Common/Location.h
Views: 1798
#pragma once12#include <AP_Math/AP_Math.h>34#define LOCATION_ALT_MAX_M 83000 // maximum altitude (in meters) that can be fit into Location structure's alt field56class Location7{8public:910uint8_t relative_alt : 1; // 1 if altitude is relative to home11uint8_t loiter_ccw : 1; // 0 if clockwise, 1 if counter clockwise12uint8_t terrain_alt : 1; // this altitude is above terrain13uint8_t origin_alt : 1; // this altitude is above ekf origin14uint8_t loiter_xtrack : 1; // 0 to crosstrack from center of waypoint, 1 to crosstrack from tangent exit location1516// note that mission storage only stores 24 bits of altitude (~ +/- 83km)17int32_t alt; // in cm18int32_t lat; // in 1E7 degrees19int32_t lng; // in 1E7 degrees2021/// enumeration of possible altitude types22enum class AltFrame {23ABSOLUTE = 0,24ABOVE_HOME = 1,25ABOVE_ORIGIN = 2,26ABOVE_TERRAIN = 327};2829/// constructors30Location() { zero(); }31Location(int32_t latitude, int32_t longitude, int32_t alt_in_cm, AltFrame frame);32Location(const Vector3f &ekf_offset_neu, AltFrame frame);33Location(const Vector3d &ekf_offset_neu, AltFrame frame);3435// set altitude36void set_alt_cm(int32_t alt_cm, AltFrame frame);37// set_alt_m - set altitude in metres38void set_alt_m(float alt_m, AltFrame frame) {39set_alt_cm(alt_m*100, frame);40}4142// get altitude (in cm) in the desired frame43// returns false on failure to get altitude in the desired frame which can only happen if the original frame or desired frame is:44// - above-terrain and the terrain database can't supply terrain height amsl45// - above-home and home is not set46// - above-origin and origin is not set47bool get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const WARN_IF_UNUSED;48// same as get_alt_cm but in metres:49bool get_alt_m(AltFrame desired_frame, float &ret_alt) const WARN_IF_UNUSED;5051// get altitude frame52AltFrame get_alt_frame() const;5354// converts altitude to new frame55// returns false on failure to convert which can only happen if the original frame or desired frame is:56// - above-terrain and the terrain database can't supply terrain height amsl57// - above-home and home is not set58// - above-origin and origin is not set59bool change_alt_frame(AltFrame desired_frame);6061// get position as a vector (in cm) from origin (x,y only or62// x,y,z) return false on failure to get the vector which can only63// happen if the EKF origin has not been set yet x, y and z are in64// centimetres. If this method returns false then vec_ne is65// unmodified.66template<typename T>67bool get_vector_xy_from_origin_NE(T &vec_ne) const WARN_IF_UNUSED;68// converts location to a vector from origin; if this method returns69// false then vec_neu is unmodified70template<typename T>71bool get_vector_from_origin_NEU(T &vec_neu) const WARN_IF_UNUSED;7273// return horizontal distance in meters between two locations74ftype get_distance(const Location &loc2) const;7576// return the altitude difference in meters taking into account alt frame.77bool get_alt_distance(const Location &loc2, ftype &distance) const WARN_IF_UNUSED;7879// return the distance in meters in North/East/Down plane as a N/E/D vector to loc280// NOT CONSIDERING ALT FRAME!81Vector3f get_distance_NED(const Location &loc2) const;82Vector3d get_distance_NED_double(const Location &loc2) const;8384// 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 085Vector3f get_distance_NED_alt_frame(const Location &loc2) const;8687// return the distance in meters in North/East plane as a N/E vector to loc288Vector2f get_distance_NE(const Location &loc2) const;89Vector2d get_distance_NE_double(const Location &loc2) const;90Vector2F get_distance_NE_ftype(const Location &loc2) const;9192// extrapolate latitude/longitude given distances (in meters) north and east93static void offset_latlng(int32_t &lat, int32_t &lng, ftype ofs_north, ftype ofs_east);94void offset(ftype ofs_north, ftype ofs_east);95// extrapolate latitude/longitude given distances (in meters) north96// and east. Note that this is metres, *even for the altitude*.97void offset(const Vector3p &ofs_ned);9899// extrapolate latitude/longitude given bearing and distance100void offset_bearing(ftype bearing_deg, ftype distance);101102// extrapolate latitude/longitude given bearing, pitch and distance103void offset_bearing_and_pitch(ftype bearing_deg, ftype pitch_deg, ftype distance);104105// longitude_scale - returns the scaler to compensate for106// shrinking longitude as you move north or south from the equator107// Note: this does not include the scaling to convert108// longitude/latitude points to meters or centimeters109static ftype longitude_scale(int32_t lat);110111bool is_zero(void) const WARN_IF_UNUSED;112113void zero(void);114115// return the bearing in radians, from 0 to 2*Pi116ftype get_bearing(const Location &loc2) const;117118// return bearing in centi-degrees from location to loc2, return is 0 to 35999119int32_t get_bearing_to(const Location &loc2) const {120return int32_t(get_bearing(loc2) * DEGX100 + 0.5);121}122123// check if lat and lng match. Ignore altitude and options124bool same_latlon_as(const Location &loc2) const;125126// check if altitude matches.127bool same_alt_as(const Location &loc2) const;128129// check if lat, lng, and alt match.130bool same_loc_as(const Location &loc2) const {131return same_latlon_as(loc2) && same_alt_as(loc2);132}133134/*135* convert invalid waypoint with useful data. return true if location changed136*/137bool sanitize(const Location &defaultLoc);138139// return true when lat and lng are within range140bool check_latlng() const;141142// see if location is past a line perpendicular to143// the line between point1 and point2 and passing through point2.144// If point1 is our previous waypoint and point2 is our target waypoint145// then this function returns true if we have flown past146// the target waypoint147bool past_interval_finish_line(const Location &point1, const Location &point2) const;148149/*150return the proportion we are along the path from point1 to151point2, along a line parallel to point1<->point2.152This will be more than 1 if we have passed point2153*/154float line_path_proportion(const Location &point1, const Location &point2) const;155156// update altitude and alt-frame base on this location's horizontal position between point1 and point2157// this location's lat,lon is used to calculate the alt of the closest point on the line between point1 and point2158// origin and destination's altitude frames must be the same159// this alt-frame will be updated to match the destination alt frame160void linearly_interpolate_alt(const Location &point1, const Location &point2);161162bool initialised() const { return (lat !=0 || lng != 0 || alt != 0); }163164// wrap longitude at -180e7 to 180e7165static int32_t wrap_longitude(int64_t lon);166167// limit latitude to -90e7 to 90e7168static int32_t limit_lattitude(int32_t lat);169170// get lon1-lon2, wrapping at -180e7 to 180e7171static int32_t diff_longitude(int32_t lon1, int32_t lon2);172173private:174175// scaling factor from 1e-7 degrees to meters at equator176// == 1.0e-7 * DEG_TO_RAD * RADIUS_OF_EARTH177static constexpr float LOCATION_SCALING_FACTOR = LATLON_TO_M;178// inverse of LOCATION_SCALING_FACTOR179static constexpr float LOCATION_SCALING_FACTOR_INV = LATLON_TO_M_INV;180};181182183