ardupilot/ArduCopter/navigation.cpp

34 lines
1.0 KiB
C++
Raw 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);
2013-10-29 01:28:27 -03:00
flightmode->update_navigation();
}
2017-12-14 07:40:46 -04:00
// distance between vehicle and home in cm
uint32_t Copter::home_distance()
{
if (position_ok()) {
const Vector3f home = pv_location_to_vector(ahrs.get_home());
const Vector3f curr = inertial_nav.get_position();
_home_distance = get_horizontal_distance_cm(curr, home);
}
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()) {
const Vector3f home = pv_location_to_vector(ahrs.get_home());
const Vector3f curr = inertial_nav.get_position();
_home_bearing = get_bearing_cd(curr,home);
}
return _home_bearing;
}