diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 4185f35e03..6a2b336b82 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -2190,8 +2190,10 @@ bool ModeAuto::verify_circle(const AP_Mission::Mission_Command& cmd) return false; } + const float turns = cmd.get_loiter_turns(); + // check if we have completed circling - return fabsf(copter.circle_nav->get_angle_total()/float(M_2PI)) >= LOWBYTE(cmd.p1); + return fabsf(copter.circle_nav->get_angle_total()/float(M_2PI)) >= turns; } // verify_spline_wp - check if we have reached the next way point using spline