AC_WPNav: remove shift_loiter_target

This commit is contained in:
Jonathan Challinger 2016-06-21 14:25:17 -07:00 committed by Randy Mackay
parent 91a5b26725
commit b5e80148c6
2 changed files with 0 additions and 12 deletions

View File

@ -168,14 +168,6 @@ void AC_WPNav::init_loiter_target(const Vector3f& position, bool reset_I)
_pilot_accel_rgt_cms = 0;
}
/// shift_loiter_target - shifts the loiter target by the given pos_adjustment
/// used by precision landing to adjust horizontal position target
void AC_WPNav::shift_loiter_target(const Vector3f &pos_adjustment)
{
// move pos controller target
_pos_control.shift_pos_xy_target(pos_adjustment.x, pos_adjustment.y);
}
/// init_loiter_target - initialize's loiter position and feed-forward velocity from current pos and velocity
void AC_WPNav::init_loiter_target()
{

View File

@ -77,10 +77,6 @@ public:
/// init_loiter_target - initialize's loiter position and feed-forward velocity from current pos and velocity
void init_loiter_target();
/// shift_loiter_target - shifts the loiter target by the given pos_adjustment
/// used by precision landing to adjust horizontal position target
void shift_loiter_target(const Vector3f &pos_adjustment);
/// loiter_soften_for_landing - reduce response for landing
void loiter_soften_for_landing();