AC_Avoidance: constify get_position

This commit is contained in:
Randy Mackay 2017-01-05 15:19:47 +09:00
parent a47e215a8e
commit 12dd6e11fb
2 changed files with 2 additions and 2 deletions

View File

@ -289,7 +289,7 @@ void AC_Avoid::limit_velocity(float kP, float accel_cmss, Vector2f &desired_vel,
/*
* Gets the current xy-position, relative to home (not relative to EKF origin)
*/
Vector2f AC_Avoid::get_position()
Vector2f AC_Avoid::get_position() const
{
const Vector3f position_xyz = _inav.get_position();
const Vector2f position_xy(position_xyz.x,position_xyz.y);

View File

@ -85,7 +85,7 @@ private:
/*
* Gets the current position, relative to home (not relative to EKF origin)
*/
Vector2f get_position();
Vector2f get_position() const;
/*
* Computes the speed such that the stopping distance