Copter: initialise target vel in loiter

This commit is contained in:
Randy Mackay 2013-05-25 14:07:04 +09:00
parent a474b97291
commit e3dffb920b
2 changed files with 9 additions and 1 deletions

View File

@ -130,6 +130,14 @@ void AC_WPNav::get_stopping_point(const Vector3f& position, const Vector3f& velo
target.z = position.z;
}
/// set_loiter_target in cm from home
void AC_WPNav::set_loiter_target(const Vector3f& position)
{
_target = position;
_target_vel.x = 0;
_target_vel.y = 0;
}
/// set_loiter_target - set initial loiter target based on current position and velocity
void AC_WPNav::set_loiter_target(const Vector3f& position, const Vector3f& velocity)
{

View File

@ -50,7 +50,7 @@ public:
const Vector3f &get_loiter_target() const { return _target; }
/// set_loiter_target in cm from home
void set_loiter_target(const Vector3f& position) { _target = position; }
void set_loiter_target(const Vector3f& position);
/// set_loiter_target - set initial loiter target based on current position and velocity
void set_loiter_target(const Vector3f& position, const Vector3f& velocity);