mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: init_loiter_target always resets I term
This was only used by poshold and this has been removed as part of "new-loiter"
This commit is contained in:
parent
1035645f5c
commit
92b56c2c89
|
@ -170,7 +170,7 @@ AC_WPNav::AC_WPNav(const AP_InertialNav& inav, const AP_AHRS_View& ahrs, AC_PosC
|
|||
///
|
||||
|
||||
/// init_loiter_target in cm from home
|
||||
void AC_WPNav::init_loiter_target(const Vector3f& position, bool reset_I)
|
||||
void AC_WPNav::init_loiter_target(const Vector3f& position)
|
||||
{
|
||||
// initialise pos controller speed, acceleration
|
||||
_pos_control.set_speed_xy(WPNAV_LOITER_VEL_CORRECTION_MAX);
|
||||
|
|
|
@ -73,8 +73,7 @@ public:
|
|||
///
|
||||
|
||||
/// init_loiter_target to a position in cm from ekf origin
|
||||
/// caller can set reset_I to false to preserve I term since previous time loiter controller ran. Should only be false when caller is sure that not too much time has passed to invalidate the I terms
|
||||
void init_loiter_target(const Vector3f& position, bool reset_I=true);
|
||||
void init_loiter_target(const Vector3f& position);
|
||||
|
||||
/// init_loiter_target - initialize's loiter position and feed-forward velocity from current pos and velocity
|
||||
void init_loiter_target();
|
||||
|
|
Loading…
Reference in New Issue