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 Randy Mackay
parent 39032459d1
commit 1edf1d265c

View File

@ -300,6 +300,10 @@ void ModeAuto::circle_start()
// initialise circle controller
copter.circle_nav->init(copter.circle_nav->get_center(), copter.circle_nav->center_is_terrain_alt());
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