mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_InertialNav: get_velocity_xy const
This commit is contained in:
parent
5fc071f5f9
commit
0e065e4894
@ -281,7 +281,7 @@ void AP_InertialNav::set_velocity_xy(float x, float y)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// set_velocity_xy - set velocity in latitude & longitude directions (in cm/s)
|
// set_velocity_xy - set velocity in latitude & longitude directions (in cm/s)
|
||||||
float AP_InertialNav::get_velocity_xy()
|
float AP_InertialNav::get_velocity_xy() const
|
||||||
{
|
{
|
||||||
return pythagorous2(_velocity.x, _velocity.y);
|
return pythagorous2(_velocity.x, _velocity.y);
|
||||||
}
|
}
|
||||||
|
@ -129,7 +129,7 @@ public:
|
|||||||
*
|
*
|
||||||
* @returns the current horizontal velocity in cm/s
|
* @returns the current horizontal velocity in cm/s
|
||||||
*/
|
*/
|
||||||
virtual float get_velocity_xy();
|
virtual float get_velocity_xy() const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* set_velocity_xy - overwrites the current horizontal velocity in cm/s
|
* set_velocity_xy - overwrites the current horizontal velocity in cm/s
|
||||||
|
@ -137,7 +137,7 @@ const Vector3f &AP_InertialNav_NavEKF::get_velocity() const
|
|||||||
*
|
*
|
||||||
* @returns the current horizontal velocity in cm/s
|
* @returns the current horizontal velocity in cm/s
|
||||||
*/
|
*/
|
||||||
float AP_InertialNav_NavEKF::get_velocity_xy()
|
float AP_InertialNav_NavEKF::get_velocity_xy() const
|
||||||
{
|
{
|
||||||
if (_ahrs.have_inertial_nav()) {
|
if (_ahrs.have_inertial_nav()) {
|
||||||
return pythagorous2(_velocity_cm.x, _velocity_cm.y);
|
return pythagorous2(_velocity_cm.x, _velocity_cm.y);
|
||||||
|
@ -84,7 +84,7 @@ public:
|
|||||||
*
|
*
|
||||||
* @returns the current horizontal velocity in cm/s
|
* @returns the current horizontal velocity in cm/s
|
||||||
*/
|
*/
|
||||||
float get_velocity_xy();
|
float get_velocity_xy() const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* altitude_ok - returns true if inertial based altitude and position can be trusted
|
* altitude_ok - returns true if inertial based altitude and position can be trusted
|
||||||
|
Loading…
Reference in New Issue
Block a user