mirror of https://github.com/ArduPilot/ardupilot
AP_InertialNav: rename to get_position_xy() & get_velocity_xy()
This commit is contained in:
parent
28d9be1cc0
commit
027336dbb8
|
@ -61,6 +61,16 @@ const Vector3f &AP_InertialNav::get_position(void) const
|
|||
return _relpos_cm;
|
||||
}
|
||||
|
||||
/**
|
||||
* get_position_xy - returns the current x-y position relative to the home location in cm.
|
||||
*
|
||||
* @return
|
||||
*/
|
||||
const Vector2f &AP_InertialNav::get_position_xy() const
|
||||
{
|
||||
return _relpos_cm.xy();
|
||||
}
|
||||
|
||||
/**
|
||||
* get_velocity - returns the current velocity in cm/s
|
||||
*
|
||||
|
@ -74,6 +84,16 @@ const Vector3f &AP_InertialNav::get_velocity() const
|
|||
return _velocity_cm;
|
||||
}
|
||||
|
||||
/**
|
||||
* get_velocity_xy - returns the current x-y velocity relative to the home location in cm.
|
||||
*
|
||||
* @return
|
||||
*/
|
||||
const Vector2f &AP_InertialNav::get_velocity_xy() const
|
||||
{
|
||||
return _velocity_cm.xy();
|
||||
}
|
||||
|
||||
/**
|
||||
* get_speed_xy - returns the current horizontal speed in cm/s
|
||||
*
|
||||
|
|
|
@ -35,6 +35,13 @@ public:
|
|||
*/
|
||||
const Vector3f& get_position() const;
|
||||
|
||||
/**
|
||||
* get_position_xy - returns the current x-y position relative to the home location in cm.
|
||||
*
|
||||
* @return
|
||||
*/
|
||||
const Vector2f& get_position_xy() const;
|
||||
|
||||
/**
|
||||
* get_velocity - returns the current velocity in cm/s
|
||||
*
|
||||
|
@ -45,6 +52,13 @@ public:
|
|||
*/
|
||||
const Vector3f& get_velocity() const;
|
||||
|
||||
/**
|
||||
* get_velocity_xy - returns the current x-y velocity relative to the home location in cm.
|
||||
*
|
||||
* @return
|
||||
*/
|
||||
const Vector2f& get_velocity_xy() const;
|
||||
|
||||
/**
|
||||
* get_speed_xy - returns the current horizontal speed in cm/s
|
||||
*
|
||||
|
|
Loading…
Reference in New Issue