Browse Source

AC_WPNav: add loiter_soften_for_landing method

This resets the position target to the current location.
mission-4.1.18
Randy Mackay 11 years ago
parent
commit
765420ee04
  1. 10
      libraries/AC_WPNav/AC_WPNav.cpp
  2. 3
      libraries/AC_WPNav/AC_WPNav.h

10
libraries/AC_WPNav/AC_WPNav.cpp

@ -176,6 +176,16 @@ void AC_WPNav::init_loiter_target() @@ -176,6 +176,16 @@ void AC_WPNav::init_loiter_target()
_pilot_accel_rgt_cms = 0;
}
/// loiter_soften_for_landing - reduce response for landing
void AC_WPNav::loiter_soften_for_landing()
{
const Vector3f& curr_pos = _inav.get_position();
// set target position to current position
_pos_control.set_xy_target(curr_pos.x, curr_pos.y);
_pos_control.freeze_ff_xy();
}
/// set_loiter_velocity - allows main code to pass the maximum velocity for loiter
void AC_WPNav::set_loiter_velocity(float velocity_cms)
{

3
libraries/AC_WPNav/AC_WPNav.h

@ -69,6 +69,9 @@ public: @@ -69,6 +69,9 @@ public:
/// init_loiter_target - initialize's loiter position and feed-forward velocity from current pos and velocity
void init_loiter_target();
/// loiter_soften_for_landing - reduce response for landing
void loiter_soften_for_landing();
/// set_loiter_velocity - allows main code to pass the maximum velocity for loiter
void set_loiter_velocity(float velocity_cms);

Loading…
Cancel
Save