mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AC_Circle: init resets desired velocity_xy
This commit is contained in:
parent
d104e3a3c0
commit
a356cfa529
@ -54,6 +54,8 @@ void AC_Circle::init(const Vector3f& center)
|
||||
_center = center;
|
||||
|
||||
// initialise position controller (sets target roll angle, pitch angle and I terms based on vehicle current lean angles)
|
||||
_pos_control.set_desired_accel_xy(0.0f,0.0f);
|
||||
_pos_control.set_desired_velocity_xy(0.0f,0.0f);
|
||||
_pos_control.init_xy_controller();
|
||||
|
||||
// set initial position target to reasonable stopping point
|
||||
@ -72,6 +74,8 @@ void AC_Circle::init(const Vector3f& center)
|
||||
void AC_Circle::init()
|
||||
{
|
||||
// initialise position controller (sets target roll angle, pitch angle and I terms based on vehicle current lean angles)
|
||||
_pos_control.set_desired_accel_xy(0.0f,0.0f);
|
||||
_pos_control.set_desired_velocity_xy(0.0f,0.0f);
|
||||
_pos_control.init_xy_controller();
|
||||
|
||||
// set initial position target to reasonable stopping point
|
||||
|
Loading…
Reference in New Issue
Block a user