Copter: Set correct yaw for circle in Mode Auto

This commit is contained in:
Rishabh 2020-04-09 16:11:06 +05:30 committed by Andrew Tridgell
parent ab6b533612
commit c42c7e40be
1 changed files with 4 additions and 0 deletions

View File

@ -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