2019-04-11 20:38:17 -03:00
# pragma once
2015-08-10 02:25:15 -03:00
# include <AP_Math/AP_Math.h>
2019-02-12 12:36:59 -04:00
# define LOCATION_ALT_MAX_M 83000 // maximum altitude (in meters) that can be fit into Location structure's alt field
2019-01-01 22:53:47 -04:00
class Location
2015-08-10 02:25:15 -03:00
{
public :
2019-01-01 22:53:47 -04:00
uint8_t relative_alt : 1 ; // 1 if altitude is relative to home
uint8_t loiter_ccw : 1 ; // 0 if clockwise, 1 if counter clockwise
uint8_t terrain_alt : 1 ; // this altitude is above terrain
uint8_t origin_alt : 1 ; // this altitude is above ekf origin
uint8_t loiter_xtrack : 1 ; // 0 to crosstrack from center of waypoint, 1 to crosstrack from tangent exit location
// note that mission storage only stores 24 bits of altitude (~ +/- 83km)
2023-12-07 03:10:04 -04:00
int32_t alt ; // in cm
int32_t lat ; // in 1E7 degrees
int32_t lng ; // in 1E7 degrees
2019-01-01 22:53:47 -04:00
2015-08-10 02:25:15 -03:00
/// enumeration of possible altitude types
2019-03-14 22:43:43 -03:00
enum class AltFrame {
ABSOLUTE = 0 ,
ABOVE_HOME = 1 ,
ABOVE_ORIGIN = 2 ,
ABOVE_TERRAIN = 3
2015-08-10 02:25:15 -03:00
} ;
/// constructors
2024-11-17 19:14:25 -04:00
Location ( ) { zero ( ) ; }
2019-03-14 22:43:43 -03:00
Location ( int32_t latitude , int32_t longitude , int32_t alt_in_cm , AltFrame frame ) ;
2021-03-17 18:15:20 -03:00
Location ( const Vector3f & ekf_offset_neu , AltFrame frame ) ;
2021-06-30 20:18:33 -03:00
Location ( const Vector3d & ekf_offset_neu , AltFrame frame ) ;
2015-08-10 02:25:15 -03:00
// set altitude
2019-03-14 22:43:43 -03:00
void set_alt_cm ( int32_t alt_cm , AltFrame frame ) ;
2024-10-28 00:01:07 -03:00
// set_alt_m - set altitude in metres
void set_alt_m ( float alt_m , AltFrame frame ) {
set_alt_cm ( alt_m * 100 , frame ) ;
}
2015-08-10 02:25:15 -03:00
2016-04-28 08:54:58 -03:00
// get altitude (in cm) in the desired frame
2022-02-03 22:45:50 -04:00
// returns false on failure to get altitude in the desired frame which can only happen if the original frame or desired frame is:
// - above-terrain and the terrain database can't supply terrain height amsl
// - above-home and home is not set
// - above-origin and origin is not set
2019-03-14 19:30:01 -03:00
bool get_alt_cm ( AltFrame desired_frame , int32_t & ret_alt_cm ) const WARN_IF_UNUSED ;
2024-04-11 06:14:02 -03:00
// same as get_alt_cm but in metres:
bool get_alt_m ( AltFrame desired_frame , float & ret_alt ) const WARN_IF_UNUSED ;
2015-08-10 02:25:15 -03:00
// get altitude frame
2019-03-14 22:43:43 -03:00
AltFrame get_alt_frame ( ) const ;
2015-08-10 02:25:15 -03:00
// converts altitude to new frame
2022-02-03 22:45:50 -04:00
// returns false on failure to convert which can only happen if the original frame or desired frame is:
// - above-terrain and the terrain database can't supply terrain height amsl
// - above-home and home is not set
// - above-origin and origin is not set
2019-03-14 22:43:43 -03:00
bool change_alt_frame ( AltFrame desired_frame ) ;
2015-08-10 02:25:15 -03:00
2024-06-05 23:39:38 -03:00
// get position as a vector (in cm) from origin (x,y only or
// x,y,z) return false on failure to get the vector which can only
// happen if the EKF origin has not been set yet x, y and z are in
// centimetres. If this method returns false then vec_ne is
// unmodified.
2024-06-06 01:43:45 -03:00
template < typename T >
bool get_vector_xy_from_origin_NE ( T & vec_ne ) const WARN_IF_UNUSED ;
2024-06-05 23:39:38 -03:00
// converts location to a vector from origin; if this method returns
// false then vec_neu is unmodified
2024-06-06 01:43:45 -03:00
template < typename T >
bool get_vector_from_origin_NEU ( T & vec_neu ) const WARN_IF_UNUSED ;
2015-08-10 02:25:15 -03:00
2022-04-23 03:04:19 -03:00
// return horizontal distance in meters between two locations
2023-02-02 18:58:38 -04:00
ftype get_distance ( const Location & loc2 ) const ;
2015-08-10 02:25:15 -03:00
2021-09-18 20:13:07 -03:00
// return the altitude difference in meters taking into account alt frame.
2023-02-02 18:58:38 -04:00
bool get_alt_distance ( const Location & loc2 , ftype & distance ) const WARN_IF_UNUSED ;
2021-09-18 20:13:07 -03:00
2019-04-08 10:27:31 -03:00
// return the distance in meters in North/East/Down plane as a N/E/D vector to loc2
2021-09-18 20:13:07 -03:00
// NOT CONSIDERING ALT FRAME!
2019-04-08 10:27:31 -03:00
Vector3f get_distance_NED ( const Location & loc2 ) const ;
2021-06-22 02:44:00 -03:00
Vector3d get_distance_NED_double ( const Location & loc2 ) const ;
2019-04-08 10:27:31 -03:00
2024-03-02 21:01:25 -04:00
// 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
Vector3f get_distance_NED_alt_frame ( const Location & loc2 ) const ;
2019-04-08 09:22:38 -03:00
// return the distance in meters in North/East plane as a N/E vector to loc2
Vector2f get_distance_NE ( const Location & loc2 ) const ;
2021-06-20 23:01:59 -03:00
Vector2d get_distance_NE_double ( const Location & loc2 ) const ;
Vector2F get_distance_NE_ftype ( const Location & loc2 ) const ;
2019-04-08 09:22:38 -03:00
2015-08-10 02:25:15 -03:00
// extrapolate latitude/longitude given distances (in meters) north and east
2021-07-09 01:58:09 -03:00
static void offset_latlng ( int32_t & lat , int32_t & lng , ftype ofs_north , ftype ofs_east ) ;
void offset ( ftype ofs_north , ftype ofs_east ) ;
2023-09-06 01:03:29 -03:00
// extrapolate latitude/longitude given distances (in meters) north
// and east. Note that this is metres, *even for the altitude*.
void offset ( const Vector3p & ofs_ned ) ;
2015-08-10 02:25:15 -03:00
2019-04-05 03:11:26 -03:00
// extrapolate latitude/longitude given bearing and distance
2021-07-12 19:05:48 -03:00
void offset_bearing ( ftype bearing_deg , ftype distance ) ;
2020-07-01 03:10:55 -03:00
// extrapolate latitude/longitude given bearing, pitch and distance
2021-07-12 19:05:48 -03:00
void offset_bearing_and_pitch ( ftype bearing_deg , ftype pitch_deg , ftype distance ) ;
2019-04-05 03:11:26 -03:00
2019-03-06 03:27:27 -04:00
// longitude_scale - returns the scaler to compensate for
// shrinking longitude as you move north or south from the equator
// Note: this does not include the scaling to convert
// longitude/latitude points to meters or centimeters
2021-07-09 01:58:09 -03:00
static ftype longitude_scale ( int32_t lat ) ;
2019-03-06 03:27:27 -04:00
2019-03-14 19:30:01 -03:00
bool is_zero ( void ) const WARN_IF_UNUSED ;
2016-07-10 19:41:20 -03:00
2019-01-01 19:57:48 -04:00
void zero ( void ) ;
2016-07-10 19:41:20 -03:00
2022-03-07 17:35:25 -04:00
// return the bearing in radians, from 0 to 2*Pi
2023-02-02 18:58:38 -04:00
ftype get_bearing ( const Location & loc2 ) const ;
2022-03-07 17:35:25 -04:00
// return bearing in centi-degrees from location to loc2, return is 0 to 35999
2023-02-02 18:58:38 -04:00
int32_t get_bearing_to ( const Location & loc2 ) const {
2022-03-07 17:35:25 -04:00
return int32_t ( get_bearing ( loc2 ) * DEGX100 + 0.5 ) ;
}
2019-04-05 10:02:42 -03:00
2019-04-08 08:45:08 -03:00
// check if lat and lng match. Ignore altitude and options
bool same_latlon_as ( const Location & loc2 ) const ;
2023-02-15 00:49:40 -04:00
// check if altitude matches.
bool same_alt_as ( const Location & loc2 ) const ;
2019-04-08 08:45:08 -03:00
2023-02-15 00:50:28 -04:00
// check if lat, lng, and alt match.
bool same_loc_as ( const Location & loc2 ) const {
return same_latlon_as ( loc2 ) & & same_alt_as ( loc2 ) ;
}
2019-03-23 00:29:18 -03:00
/*
* convert invalid waypoint with useful data . return true if location changed
*/
2023-02-02 18:58:38 -04:00
bool sanitize ( const Location & defaultLoc ) ;
2019-03-23 00:29:18 -03:00
2019-04-08 10:51:23 -03:00
// return true when lat and lng are within range
bool check_latlng ( ) const ;
2019-04-09 05:24:22 -03:00
// see if location is past a line perpendicular to
// the line between point1 and point2 and passing through point2.
// If point1 is our previous waypoint and point2 is our target waypoint
// then this function returns true if we have flown past
// the target waypoint
bool past_interval_finish_line ( const Location & point1 , const Location & point2 ) const ;
2019-04-09 05:24:44 -03:00
/*
return the proportion we are along the path from point1 to
point2 , along a line parallel to point1 < - > point2 .
This will be more than 1 if we have passed point2
*/
float line_path_proportion ( const Location & point1 , const Location & point2 ) const ;
2021-03-19 04:57:36 -03:00
// update altitude and alt-frame base on this location's horizontal position between point1 and point2
// this location's lat,lon is used to calculate the alt of the closest point on the line between point1 and point2
// origin and destination's altitude frames must be the same
// this alt-frame will be updated to match the destination alt frame
void linearly_interpolate_alt ( const Location & point1 , const Location & point2 ) ;
2019-09-12 22:02:36 -03:00
bool initialised ( ) const { return ( lat ! = 0 | | lng ! = 0 | | alt ! = 0 ) ; }
2019-06-15 04:59:32 -03:00
2021-06-22 21:14:42 -03:00
// wrap longitude at -180e7 to 180e7
2021-06-20 23:01:59 -03:00
static int32_t wrap_longitude ( int64_t lon ) ;
2021-06-22 21:14:42 -03:00
2023-10-11 04:41:51 -03:00
// limit latitude to -90e7 to 90e7
2021-06-20 23:01:59 -03:00
static int32_t limit_lattitude ( int32_t lat ) ;
2021-06-22 21:14:42 -03:00
// get lon1-lon2, wrapping at -180e7 to 180e7
static int32_t diff_longitude ( int32_t lon1 , int32_t lon2 ) ;
2021-07-09 01:58:09 -03:00
2015-08-10 02:25:15 -03:00
private :
2019-04-12 05:35:30 -03:00
// scaling factor from 1e-7 degrees to meters at equator
// == 1.0e-7 * DEG_TO_RAD * RADIUS_OF_EARTH
2021-06-29 03:21:43 -03:00
static constexpr float LOCATION_SCALING_FACTOR = LATLON_TO_M ;
2019-04-12 05:35:30 -03:00
// inverse of LOCATION_SCALING_FACTOR
2021-06-29 03:21:43 -03:00
static constexpr float LOCATION_SCALING_FACTOR_INV = LATLON_TO_M_INV ;
2015-08-10 02:25:15 -03:00
} ;