mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-25 09:13:57 -04:00
AC_Avoidance: constify get_position
This commit is contained in:
parent
a47e215a8e
commit
12dd6e11fb
@ -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);
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user