APM:Copter
navigation.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 // run_nav_updates - top level call for the autopilot
4 // ensures calculations such as "distance to waypoint" are calculated before autopilot makes decisions
5 // To-Do - rename and move this function to make it's purpose more clear
7 {
9 
11 }
12 
13 // distance between vehicle and home in cm
15 {
16  if (position_ok()) {
18  const Vector3f curr = inertial_nav.get_position();
20  }
21  return _home_distance;
22 }
23 
24 // The location of home in relation to the vehicle in centi-degrees
26 {
27  if (position_ok()) {
29  const Vector3f curr = inertial_nav.get_position();
30  _home_bearing = get_bearing_cd(curr,home);
31  }
32  return _home_bearing;
33 }
AP_AHRS_NavEKF ahrs
Definition: Copter.h:255
const struct Location & get_home(void) const
AP_InertialNav_NavEKF inertial_nav
Definition: Copter.h:483
int32_t get_bearing_cd(const struct Location &loc1, const struct Location &loc2)
const Vector3f & get_position() const
float get_horizontal_distance_cm(const Vector3f &origin, const Vector3f &destination)
Mode * flightmode
Definition: Copter.h:955
void run_nav_updates(void)
Definition: navigation.cpp:6
void update_super_simple_bearing(bool force_update)
Definition: ArduCopter.cpp:532
Vector3f pv_location_to_vector(const Location &loc)
uint32_t home_distance()
Definition: navigation.cpp:14
bool position_ok()
Definition: system.cpp:312
int32_t home_bearing()
Definition: navigation.cpp:25
uint32_t _home_distance
Definition: Copter.h:430
void update_navigation()
Definition: mode.cpp:318
int32_t _home_bearing
Definition: Copter.h:429