diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index 4c1c4dc1dd..9ad1001fab 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -320,6 +320,10 @@ void ModeAuto::circle_start() // initialise circle controller copter.circle_nav->init(copter.circle_nav->get_center()); + + if (auto_yaw.mode() != AUTO_YAW_ROI) { + auto_yaw.set_mode(AUTO_YAW_HOLD); + } } // auto_spline_start - initialises waypoint controller to implement flying to a particular destination using the spline controller