Browse Source

Copter: Set correct yaw for circle in Mode Auto

copter407
Rishabh 5 years ago committed by Randy Mackay
parent
commit
23900e5194
  1. 4
      ArduCopter/mode_auto.cpp

4
ArduCopter/mode_auto.cpp

@ -320,6 +320,10 @@ void ModeAuto::circle_start() @@ -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

Loading…
Cancel
Save