From 7765399e497f9a95726cf41264c9fee9e48b0afc Mon Sep 17 00:00:00 2001 From: Shiv Tyagi Date: Sun, 6 Feb 2022 22:05:17 +0530 Subject: [PATCH] Copter: change circle_nav.set_radius to circle_nav.set_radius_cm --- ArduCopter/mode_auto.cpp | 2 +- ArduCopter/mode_circle.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 9d449ef770..9d2d1a590a 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -378,7 +378,7 @@ void ModeAuto::circle_movetoedge_start(const Location &circle_center, float radi // set circle radius if (!is_zero(radius_m)) { - copter.circle_nav->set_radius(radius_m * 100.0f); + copter.circle_nav->set_radius_cm(radius_m * 100.0f); } // check our distance from edge of circle diff --git a/ArduCopter/mode_circle.cpp b/ArduCopter/mode_circle.cpp index 6b31b95c76..eca217bc05 100644 --- a/ArduCopter/mode_circle.cpp +++ b/ArduCopter/mode_circle.cpp @@ -52,7 +52,7 @@ void ModeCircle::run() const float radius_new = MAX(radius_current + radius_pilot_change,0); // new radius target if (!is_equal(radius_current, radius_new)) { - copter.circle_nav->set_radius(radius_new); + copter.circle_nav->set_radius_cm(radius_new); } // update the orbicular rate target based on pilot roll stick inputs