AC_Loiter: init_target only inits pos controller if inactive

this reduces a twitch found during the development of zig-zag mode
This commit is contained in:
Randy Mackay 2018-10-04 19:54:32 +09:00
parent d3f7214bcf
commit f0181be9c9
1 changed files with 4 additions and 2 deletions

View File

@ -106,8 +106,10 @@ void AC_Loiter::init_target(const Vector3f& position)
_pos_control.set_desired_velocity_xy(0.0f,0.0f);
_pos_control.set_desired_accel_xy(0.0f,0.0f);
// initialise position controller
_pos_control.init_xy_controller();
// initialise position controller if not already active
if (!_pos_control.is_active_xy()) {
_pos_control.init_xy_controller();
}
}
/// initialize's position and feed-forward velocity from current pos and velocity