ardupilot/ArduCopter/navigation.cpp

28 lines
773 B
C++
Raw Permalink Normal View History

#include "Copter.h"
// run_nav_updates - top level call for the autopilot
// ensures calculations such as "distance to waypoint" are calculated before autopilot makes decisions
// To-Do - rename and move this function to make it's purpose more clear
void Copter::run_nav_updates(void)
{
update_super_simple_bearing(false);
}
2017-12-14 07:40:46 -04:00
// distance between vehicle and home in cm
uint32_t Copter::home_distance()
{
if (position_ok()) {
_home_distance = current_loc.get_distance(ahrs.get_home()) * 100;
}
return _home_distance;
}
2017-12-14 07:40:46 -04:00
// The location of home in relation to the vehicle in centi-degrees
int32_t Copter::home_bearing()
{
if (position_ok()) {
_home_bearing = current_loc.get_bearing_to(ahrs.get_home());
}
return _home_bearing;
}