Browse Source

AP_InertialNav: rename get_velocity_xy to get_speed_xy

A velocity is a vector - since we return just a float, this is a speed
mission-4.1.18
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
59cd9ad0a6
  1. 6
      libraries/AP_InertialNav/AP_InertialNav.h
  2. 6
      libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp
  3. 6
      libraries/AP_InertialNav/AP_InertialNav_NavEKF.h

6
libraries/AP_InertialNav/AP_InertialNav.h

@ -86,11 +86,11 @@ public: @@ -86,11 +86,11 @@ public:
virtual const Vector3f& get_velocity() const = 0;
/**
* get_velocity_xy - returns the current horizontal velocity in cm/s
* get_speed_xy - returns the current horizontal speed in cm/s
*
* @returns the current horizontal velocity in cm/s
* @returns the current horizontal speed in cm/s
*/
virtual float get_velocity_xy() const = 0;
virtual float get_speed_xy() const = 0;
//
// Z Axis methods

6
libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp

@ -118,11 +118,11 @@ const Vector3f &AP_InertialNav_NavEKF::get_velocity() const @@ -118,11 +118,11 @@ const Vector3f &AP_InertialNav_NavEKF::get_velocity() const
}
/**
* get_velocity_xy - returns the current horizontal velocity in cm/s
* get_speed_xy - returns the current horizontal speed in cm/s
*
* @returns the current horizontal velocity in cm/s
* @returns the current horizontal speed in cm/s
*/
float AP_InertialNav_NavEKF::get_velocity_xy() const
float AP_InertialNav_NavEKF::get_speed_xy() const
{
return norm(_velocity_cm.x, _velocity_cm.y);
}

6
libraries/AP_InertialNav/AP_InertialNav_NavEKF.h

@ -76,11 +76,11 @@ public: @@ -76,11 +76,11 @@ public:
float get_pos_z_derivative() const;
/**
* get_velocity_xy - returns the current horizontal velocity in cm/s
* get_speed_xy - returns the current horizontal speed in cm/s
*
* @returns the current horizontal velocity in cm/s
* @returns the current horizontal speed in cm/s
*/
float get_velocity_xy() const override;
float get_speed_xy() const override;
/**
* get_altitude - get latest altitude estimate in cm

Loading…
Cancel
Save