mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_InertialNav: rename for neu & cm/cms
This commit is contained in:
parent
e10edabd5d
commit
04ba26a080
@ -52,75 +52,73 @@ nav_filter_status AP_InertialNav::get_filter_status() const
|
|||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_position - returns the current position relative to the home location in cm.
|
* get_position_neu_cm - returns the current position relative to the home location in cm.
|
||||||
*
|
*
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
const Vector3f &AP_InertialNav::get_position(void) const
|
const Vector3f &AP_InertialNav::get_position_neu_cm(void) const
|
||||||
{
|
{
|
||||||
return _relpos_cm;
|
return _relpos_cm;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_position_xy - returns the current x-y position relative to the home location in cm.
|
* get_position_xy_cm - returns the current x-y position relative to the home location in cm.
|
||||||
*
|
*
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
const Vector2f &AP_InertialNav::get_position_xy() const
|
const Vector2f &AP_InertialNav::get_position_xy_cm() const
|
||||||
{
|
{
|
||||||
return _relpos_cm.xy();
|
return _relpos_cm.xy();
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_velocity - returns the current velocity in cm/s
|
* get_position_z_up_cm - returns the current z position relative to the home location, frame z-axis up, in cm.
|
||||||
|
* @return
|
||||||
|
*/
|
||||||
|
float AP_InertialNav::get_position_z_up_cm() const
|
||||||
|
{
|
||||||
|
return _relpos_cm.z;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get_velocity_neu_cms - returns the current velocity in cm/s
|
||||||
*
|
*
|
||||||
* @return velocity vector:
|
* @return velocity vector:
|
||||||
* .x : latitude velocity in cm/s
|
* .x : latitude velocity in cm/s
|
||||||
* .y : longitude velocity in cm/s
|
* .y : longitude velocity in cm/s
|
||||||
* .z : vertical velocity in cm/s
|
* .z : vertical velocity in cm/s
|
||||||
*/
|
*/
|
||||||
const Vector3f &AP_InertialNav::get_velocity() const
|
const Vector3f &AP_InertialNav::get_velocity_neu_cms() const
|
||||||
{
|
{
|
||||||
return _velocity_cm;
|
return _velocity_cm;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_velocity_xy - returns the current x-y velocity relative to the home location in cm.
|
* get_velocity_xy_cms - returns the current x-y velocity relative to the home location in cm.
|
||||||
*
|
*
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
const Vector2f &AP_InertialNav::get_velocity_xy() const
|
const Vector2f &AP_InertialNav::get_velocity_xy_cms() const
|
||||||
{
|
{
|
||||||
return _velocity_cm.xy();
|
return _velocity_cm.xy();
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_speed_xy - returns the current horizontal speed in cm/s
|
* get_speed_xy_cms - returns the current horizontal speed in cm/s
|
||||||
*
|
*
|
||||||
* @returns the current horizontal speed in cm/s
|
* @returns the current horizontal speed in cm/s
|
||||||
*/
|
*/
|
||||||
float AP_InertialNav::get_speed_xy() const
|
float AP_InertialNav::get_speed_xy_cms() const
|
||||||
{
|
{
|
||||||
return _velocity_cm.xy().length();
|
return _velocity_cm.xy().length();
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_altitude - get latest altitude estimate in cm
|
* get_velocity_z_up_cms - returns the current z-axis velocity, frame z-axis up, in cm/s
|
||||||
* @return
|
|
||||||
*/
|
|
||||||
float AP_InertialNav::get_altitude() const
|
|
||||||
{
|
|
||||||
return _relpos_cm.z;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* get_velocity_z - returns the current climbrate.
|
|
||||||
*
|
*
|
||||||
* @see get_velocity().z
|
* @return z-axis velocity, frame z-axis up, in cm/s
|
||||||
*
|
|
||||||
* @return climbrate in cm/s
|
|
||||||
*/
|
*/
|
||||||
float AP_InertialNav::get_velocity_z() const
|
float AP_InertialNav::get_velocity_z_up_cms() const
|
||||||
{
|
{
|
||||||
return _velocity_cm.z;
|
return _velocity_cm.z;
|
||||||
}
|
}
|
||||||
|
@ -27,59 +27,57 @@ public:
|
|||||||
nav_filter_status get_filter_status() const;
|
nav_filter_status get_filter_status() const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_position - returns the current position relative to the home location in cm.
|
* get_position_neu_cm - returns the current position relative to the home location in cm.
|
||||||
*
|
*
|
||||||
* the home location was set with AP_InertialNav::set_home_position(int32_t, int32_t)
|
* the home location was set with AP_InertialNav::set_home_position(int32_t, int32_t)
|
||||||
*
|
*
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
const Vector3f& get_position() const;
|
const Vector3f& get_position_neu_cm() const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_position_xy - returns the current x-y position relative to the home location in cm.
|
* get_position_xy_cm - returns the current x-y position relative to the home location in cm.
|
||||||
*
|
*
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
const Vector2f& get_position_xy() const;
|
const Vector2f& get_position_xy_cm() const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_velocity - returns the current velocity in cm/s
|
* get_position_z_up_cm - returns the current z position relative to the home location, frame z up, in cm.
|
||||||
|
* @return
|
||||||
|
*/
|
||||||
|
float get_position_z_up_cm() const;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* get_velocity_neu_cms - returns the current velocity in cm/s
|
||||||
*
|
*
|
||||||
* @return velocity vector:
|
* @return velocity vector:
|
||||||
* .x : latitude velocity in cm/s
|
* .x : latitude velocity in cm/s
|
||||||
* .y : longitude velocity in cm/s
|
* .y : longitude velocity in cm/s
|
||||||
* .z : vertical velocity in cm/s
|
* .z : vertical velocity in cm/s
|
||||||
*/
|
*/
|
||||||
const Vector3f& get_velocity() const;
|
const Vector3f& get_velocity_neu_cms() const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_velocity_xy - returns the current x-y velocity relative to the home location in cm.
|
* get_velocity_xy_cms - returns the current x-y velocity relative to the home location in cm.
|
||||||
*
|
*
|
||||||
* @return
|
* @return
|
||||||
*/
|
*/
|
||||||
const Vector2f& get_velocity_xy() const;
|
const Vector2f& get_velocity_xy_cms() const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_speed_xy - returns the current horizontal speed in cm/s
|
* get_speed_xy_cms - returns the current horizontal speed in cm/s
|
||||||
*
|
*
|
||||||
* @returns the current horizontal speed in cm/s
|
* @returns the current horizontal speed in cm/s
|
||||||
*/
|
*/
|
||||||
float get_speed_xy() const;
|
float get_speed_xy_cms() const;
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* get_altitude - get latest altitude estimate in cm
|
* get_velocity_z_up_cms - returns the current z-axis velocity, frame z-axis up, in cm/s
|
||||||
* @return
|
|
||||||
*/
|
|
||||||
float get_altitude() const;
|
|
||||||
|
|
||||||
/**
|
|
||||||
* get_velocity_z - returns the current climbrate.
|
|
||||||
*
|
*
|
||||||
* @see get_velocity().z
|
* @return z-axis velocity, frame z-axis up, in cm/s
|
||||||
*
|
|
||||||
* @return climbrate in cm/s
|
|
||||||
*/
|
*/
|
||||||
float get_velocity_z() const;
|
float get_velocity_z_up_cms() const;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
Vector3f _relpos_cm; // NEU
|
Vector3f _relpos_cm; // NEU
|
||||||
|
Loading…
Reference in New Issue
Block a user