Browse Source

Copter: change circle_nav.set_radius to circle_nav.set_radius_cm

apm_2208
Shiv Tyagi 3 years ago committed by Randy Mackay
parent
commit
7765399e49
  1. 2
      ArduCopter/mode_auto.cpp
  2. 2
      ArduCopter/mode_circle.cpp

2
ArduCopter/mode_auto.cpp

@ -378,7 +378,7 @@ void ModeAuto::circle_movetoedge_start(const Location &circle_center, float radi @@ -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

2
ArduCopter/mode_circle.cpp

@ -52,7 +52,7 @@ void ModeCircle::run() @@ -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

Loading…
Cancel
Save