2015-05-29 23:12:49 -03:00
|
|
|
#include "Copter.h"
|
|
|
|
|
2013-02-18 01:58:24 -04:00
|
|
|
// 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
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::run_nav_updates(void)
|
2013-01-08 01:45:12 -04:00
|
|
|
{
|
2013-02-18 01:58:24 -04:00
|
|
|
// calculate distance and bearing for reporting and autopilot decisions
|
2014-04-17 10:22:05 -03:00
|
|
|
calc_home_distance_and_bearing();
|
2013-10-29 01:28:27 -03:00
|
|
|
|
2017-12-05 21:28:32 -04:00
|
|
|
flightmode->update_navigation();
|
2014-04-17 10:22:05 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// calc_home_distance_and_bearing - calculate distance and bearing to home for reporting and autopilot decisions
|
2015-05-29 23:12:49 -03:00
|
|
|
void Copter::calc_home_distance_and_bearing()
|
2014-04-17 10:22:05 -03:00
|
|
|
{
|
2013-01-28 02:59:55 -04:00
|
|
|
// calculate home distance and bearing
|
2015-01-02 07:43:50 -04:00
|
|
|
if (position_ok()) {
|
2015-02-02 22:12:31 -04:00
|
|
|
Vector3f home = pv_location_to_vector(ahrs.get_home());
|
2015-07-08 03:22:16 -03:00
|
|
|
Vector3f curr = inertial_nav.get_position();
|
2017-12-03 17:07:39 -04:00
|
|
|
home_distance = get_horizontal_distance_cm(curr, home);
|
|
|
|
home_bearing = get_bearing_cd(curr,home);
|
2012-12-08 01:23:32 -04:00
|
|
|
|
2013-01-28 02:59:55 -04:00
|
|
|
// update super simple bearing (if required) because it relies on home_bearing
|
2013-10-05 06:25:03 -03:00
|
|
|
update_super_simple_bearing(false);
|
2013-02-18 01:58:24 -04:00
|
|
|
}
|
2012-04-19 01:06:15 -03:00
|
|
|
}
|