From 92b56c2c89579dcd71271c868689061af4c54c59 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 6 Feb 2018 15:23:32 +0900 Subject: [PATCH] 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" --- libraries/AC_WPNav/AC_WPNav.cpp | 2 +- libraries/AC_WPNav/AC_WPNav.h | 3 +-- 2 files changed, 2 insertions(+), 3 deletions(-) diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 6b057b31a4..849a066580 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -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); diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index f746c7d708..57058ab370 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -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();