APM:Libraries
Public Types | Public Member Functions | Static Public Member Functions | Static Private Attributes | List of all members
Location_Class Class Reference

#include <Location.h>

Inheritance diagram for Location_Class:
[legend]
Collaboration diagram for Location_Class:
[legend]

Public Types

enum  ALT_FRAME { ALT_FRAME_ABSOLUTE = 0, ALT_FRAME_ABOVE_HOME = 1, ALT_FRAME_ABOVE_ORIGIN = 2, ALT_FRAME_ABOVE_TERRAIN = 3 }
 enumeration of possible altitude types More...
 

Public Member Functions

 Location_Class ()
 constructors More...
 
 Location_Class (int32_t latitude, int32_t longitude, int32_t alt_in_cm, ALT_FRAME frame)
 
 Location_Class (const Location &loc)
 
 Location_Class (const Vector3f &ekf_offset_neu)
 
Location_Classoperator= (const struct Location &loc)
 
void set_alt_cm (int32_t alt_cm, ALT_FRAME frame)
 
bool get_alt_cm (ALT_FRAME desired_frame, int32_t &ret_alt_cm) const
 get altitude in desired frame More...
 
ALT_FRAME get_alt_frame () const
 
bool change_alt_frame (ALT_FRAME desired_frame)
 
bool get_vector_xy_from_origin_NE (Vector2f &vec_ne) const
 
bool get_vector_from_origin_NEU (Vector3f &vec_neu) const
 
float get_distance (const struct Location &loc2) const
 
void offset (float ofs_north, float ofs_east)
 
bool is_zero (void)
 
void zero (void)
 

Static Public Member Functions

static void set_ahrs (const AP_AHRS_NavEKF *ahrs)
 accept reference to ahrs and (indirectly) EKF More...
 
static void set_terrain (AP_Terrain *terrain)
 

Static Private Attributes

static const AP_AHRS_NavEKF_ahrs = nullptr
 
static AP_Terrain * _terrain = nullptr
 

Additional Inherited Members

- Public Attributes inherited from Location
union {
   Location_Option_Flags   flags
 options bitmask (1<<0 = relative altitude) More...
 
   uint8_t   options
 
}; 
 
int32_t alt:24
 param 2 - Altitude in centimeters (meters * 100) see LOCATION_ALT_MAX_M More...
 
int32_t lat
 param 3 - Latitude * 10**7 More...
 
int32_t lng
 param 4 - Longitude * 10**7 More...
 

Detailed Description

Definition at line 17 of file Location.h.

Member Enumeration Documentation

◆ ALT_FRAME

enumeration of possible altitude types

Enumerator
ALT_FRAME_ABSOLUTE 
ALT_FRAME_ABOVE_HOME 
ALT_FRAME_ABOVE_ORIGIN 
ALT_FRAME_ABOVE_TERRAIN 

Definition at line 22 of file Location.h.

Constructor & Destructor Documentation

◆ Location_Class() [1/4]

Location_Class::Location_Class ( )

constructors

Definition at line 16 of file Location.cpp.

Here is the call graph for this function:

◆ Location_Class() [2/4]

Location_Class::Location_Class ( int32_t  latitude,
int32_t  longitude,
int32_t  alt_in_cm,
ALT_FRAME  frame 
)

Definition at line 21 of file Location.cpp.

Here is the call graph for this function:

◆ Location_Class() [3/4]

Location_Class::Location_Class ( const Location loc)

Definition at line 29 of file Location.cpp.

◆ Location_Class() [4/4]

Location_Class::Location_Class ( const Vector3f ekf_offset_neu)

Definition at line 37 of file Location.cpp.

Here is the call graph for this function:

Member Function Documentation

◆ change_alt_frame()

bool Location_Class::change_alt_frame ( ALT_FRAME  desired_frame)

Definition at line 88 of file Location.cpp.

Referenced by AC_WPNav::set_spline_destination(), and set_terrain().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_alt_cm()

bool Location_Class::get_alt_cm ( ALT_FRAME  desired_frame,
int32_t &  ret_alt_cm 
) const

get altitude in desired frame

Definition at line 114 of file Location.cpp.

Referenced by change_alt_frame(), AC_Fence::check_destination_within_fence(), get_vector_from_origin_NEU(), AC_WPNav::get_vector_NEU(), and set_terrain().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_alt_frame()

Location_Class::ALT_FRAME Location_Class::get_alt_frame ( ) const

Definition at line 99 of file Location.cpp.

Referenced by get_alt_cm(), AC_WPNav::get_vector_NEU(), AC_WPNav::set_spline_destination(), and set_terrain().

Here is the caller graph for this function:

◆ get_distance()

float Location_Class::get_distance ( const struct Location loc2) const

Definition at line 224 of file Location.cpp.

Referenced by AP_ADSB::determine_furthest_aircraft(), AP_ADSB::handle_vehicle(), and set_terrain().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_vector_from_origin_NEU()

bool Location_Class::get_vector_from_origin_NEU ( Vector3f vec_neu) const

Definition at line 203 of file Location.cpp.

Referenced by set_terrain().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_vector_xy_from_origin_NE()

bool Location_Class::get_vector_xy_from_origin_NE ( Vector2f vec_ne) const

Definition at line 192 of file Location.cpp.

Referenced by AC_Fence::check_destination_within_fence(), get_vector_from_origin_NEU(), AC_WPNav::get_vector_NEU(), and set_terrain().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ is_zero()

bool Location_Class::is_zero ( void  )
inline

Definition at line 71 of file Location.h.

Referenced by AP_ADSB::handle_vehicle(), and AP_ADSB::update().

Here is the caller graph for this function:

◆ offset()

void Location_Class::offset ( float  ofs_north,
float  ofs_east 
)

Definition at line 232 of file Location.cpp.

Referenced by AC_WPNav::get_wp_destination(), Location_Class(), and set_terrain().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ operator=()

Location_Class & Location_Class::operator= ( const struct Location loc)

Definition at line 53 of file Location.cpp.

Referenced by set_terrain().

Here is the caller graph for this function:

◆ set_ahrs()

static void Location_Class::set_ahrs ( const AP_AHRS_NavEKF ahrs)
inlinestatic

accept reference to ahrs and (indirectly) EKF

Definition at line 36 of file Location.h.

◆ set_alt_cm()

void Location_Class::set_alt_cm ( int32_t  alt_cm,
ALT_FRAME  frame 
)

Definition at line 62 of file Location.cpp.

Referenced by change_alt_frame(), Location_Class(), and set_terrain().

Here is the caller graph for this function:

◆ set_terrain()

static void Location_Class::set_terrain ( AP_Terrain *  terrain)
inlinestatic

Definition at line 37 of file Location.h.

Here is the call graph for this function:

◆ zero()

void Location_Class::zero ( void  )
inline

Definition at line 73 of file Location.h.

Referenced by Location_Class(), and AP_ADSB::update().

Here is the caller graph for this function:

Member Data Documentation

◆ _ahrs

const AP_AHRS_NavEKF * Location_Class::_ahrs = nullptr
staticprivate

Definition at line 76 of file Location.h.

Referenced by get_alt_cm(), get_vector_xy_from_origin_NE(), Location_Class(), and set_ahrs().

◆ _terrain

AP_Terrain * Location_Class::_terrain = nullptr
staticprivate

Definition at line 77 of file Location.h.

Referenced by get_alt_cm(), and set_terrain().


The documentation for this class was generated from the following files: