AC_WPNav: rename set_loiter_target to init_loiter_target
This commit is contained in:
parent
63135a044f
commit
597d5227f5
@ -114,8 +114,8 @@ AC_WPNav::AC_WPNav(const AP_InertialNav& inav, const AP_AHRS& ahrs, AC_PosContro
|
||||
/// loiter controller
|
||||
///
|
||||
|
||||
/// set_loiter_target in cm from home
|
||||
void AC_WPNav::set_loiter_target(const Vector3f& position, bool reset_I)
|
||||
/// init_loiter_target in cm from home
|
||||
void AC_WPNav::init_loiter_target(const Vector3f& position, bool reset_I)
|
||||
{
|
||||
// if reset_I is false we warn position controller not to reset I terms
|
||||
if (!reset_I) {
|
||||
|
@ -58,9 +58,9 @@ public:
|
||||
/// loiter controller
|
||||
///
|
||||
|
||||
/// set_loiter_target in cm from home
|
||||
/// init_loiter_target to a position in cm from home
|
||||
/// 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 set_loiter_target(const Vector3f& position, bool reset_I=true);
|
||||
void init_loiter_target(const Vector3f& position, bool reset_I=true);
|
||||
|
||||
/// 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
Block a user