AntennaTracker: move get_bearing_cd to Location and rename to get_bearing_to

This commit is contained in:
Pierre Kancir 2019-04-05 15:02:44 +02:00 committed by Peter Barker
parent 492c7532eb
commit dfdef294e3
1 changed files with 1 additions and 1 deletions

View File

@ -54,7 +54,7 @@ void Tracker::update_bearing_and_distance()
// calculate bearing to vehicle
// To-Do: remove need for check of control_mode
if (control_mode != SCAN && !nav_status.manual_control_yaw) {
nav_status.bearing = get_bearing_cd(current_loc, vehicle.location_estimate) * 0.01f;
nav_status.bearing = current_loc.get_bearing_to(vehicle.location_estimate) * 0.01f;
}
// calculate distance to vehicle