mirror of https://github.com/ArduPilot/ardupilot
Copter: Set correct yaw for circle in Mode Auto
This commit is contained in:
parent
9750f99b91
commit
23900e5194
|
@ -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…
Reference in New Issue