diff --git a/ArduSub/mode_auto.cpp b/ArduSub/mode_auto.cpp index d1fdc42f2a..67f9e4d782 100644 --- a/ArduSub/mode_auto.cpp +++ b/ArduSub/mode_auto.cpp @@ -187,8 +187,8 @@ void ModeAuto::auto_circle_movetoedge_start(const Location &circle_center, float // check our distance from edge of circle Vector3f circle_edge_neu; - sub.circle_nav.get_closest_point_on_circle(circle_edge_neu); - float dist_to_edge = (inertial_nav.get_position_neu_cm() - circle_edge_neu).length(); + float dist_to_edge; + sub.circle_nav.get_closest_point_on_circle(circle_edge_neu, dist_to_edge); // if more than 3m then fly to edge if (dist_to_edge > 300.0f) {