From d88e12b206f2e42deb5baeebe10c44a1235f3080 Mon Sep 17 00:00:00 2001 From: Peter Hall <33176108+IamPete1@users.noreply.github.com> Date: Fri, 23 Aug 2019 11:49:34 +0100 Subject: [PATCH] Rover: mode: use oa_wp_bearing_cd --- APMrover2/mode.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/mode.cpp b/APMrover2/mode.cpp index 71ff592639..fc3101d1c8 100644 --- a/APMrover2/mode.cpp +++ b/APMrover2/mode.cpp @@ -394,7 +394,7 @@ void Mode::navigate_to_waypoint() desired_speed = calc_speed_nudge(desired_speed, g2.wp_nav.get_reversed()); calc_throttle(desired_speed, true); - float desired_heading_cd = g2.wp_nav.wp_bearing_cd(); + float desired_heading_cd = g2.wp_nav.oa_wp_bearing_cd(); if (g2.sailboat.use_indirect_route(desired_heading_cd)) { // sailboats use heading controller when tacking upwind desired_heading_cd = g2.sailboat.calc_heading(desired_heading_cd);