diff --git a/AntennaTracker/tracking.cpp b/AntennaTracker/tracking.cpp index ab427f2e27..81e41827aa 100644 --- a/AntennaTracker/tracking.cpp +++ b/AntennaTracker/tracking.cpp @@ -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