APM:Copter
position_vector.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // Position vectors related utility functions
4 
5 // position vectors are Vector3f
6 // .x = latitude from home in cm
7 // .y = longitude from home in cm
8 // .z = altitude above home in cm
9 
10 // pv_location_to_vector - convert lat/lon coordinates to a position vector
12 {
13  const struct Location &origin = inertial_nav.get_origin();
14  float alt_above_origin = pv_alt_above_origin(loc.alt); // convert alt-relative-to-home to alt-relative-to-origin
15  return Vector3f((loc.lat-origin.lat) * LATLON_TO_CM, (loc.lng-origin.lng) * LATLON_TO_CM * scaleLongDown, alt_above_origin);
16 }
17 
18 // pv_alt_above_origin - convert altitude above home to altitude above EKF origin
19 float Copter::pv_alt_above_origin(float alt_above_home_cm)
20 {
21  const struct Location &origin = inertial_nav.get_origin();
22  return alt_above_home_cm + (ahrs.get_home().alt - origin.alt);
23 }
24 
25 // pv_alt_above_home - convert altitude above EKF origin to altitude above home
26 float Copter::pv_alt_above_home(float alt_above_origin_cm)
27 {
28  const struct Location &origin = inertial_nav.get_origin();
29  return alt_above_origin_cm + (origin.alt - ahrs.get_home().alt);
30 }
31 
32 // returns distance between a destination and home in cm
33 float Copter::pv_distance_to_home_cm(const Vector3f &destination)
34 {
36  return get_horizontal_distance_cm(home, destination);
37 }
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
struct Location get_origin() const
const struct Location & get_home(void) const
AP_InertialNav_NavEKF inertial_nav
Definition: Copter.h:483
int32_t lat
float get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination)
int32_t alt
float pv_distance_to_home_cm(const Vector3f &destination)
float scaleLongDown
Definition: Copter.h:427
float pv_alt_above_home(float alt_above_origin_cm)
float pv_alt_above_origin(float alt_above_home_cm)
int32_t lng
Vector3f pv_location_to_vector(const Location &loc)
#define LATLON_TO_CM