All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Types | Public Member Functions | Static Public Member Functions | List of all members
gazebo::common::SphericalCoordinates Class Reference

Convert spherical coordinates for planetary surfaces. More...

#include <commmon/common.hh>

Public Types

enum  SurfaceType { EARTH_WGS84 = 1 }
 Unique identifiers for planetary surface models. More...
 

Public Member Functions

 SphericalCoordinates ()
 Constructor. More...
 
 SphericalCoordinates (const SurfaceType _type)
 Constructor with surface type input. More...
 
 SphericalCoordinates (const SurfaceType _type, const math::Angle &_latitude, const math::Angle &_longitude, double _elevation, const math::Angle &_heading)
 Constructor with surface type, angle, and elevation inputs. More...
 
 ~SphericalCoordinates ()
 Destructor. More...
 
double GetElevationReference () const
 Get reference elevation in meters. More...
 
math::Angle GetHeadingOffset () const
 Get heading offset for gazebo reference frame, expressed as angle from East to gazebo x-axis, or equivalently from North to gazebo y-axis. More...
 
math::Angle GetLatitudeReference () const
 Get reference geodetic latitude. More...
 
math::Angle GetLongitudeReference () const
 Get reference longitude. More...
 
SurfaceType GetSurfaceType () const
 Get SurfaceType currently in use. More...
 
math::Vector3 GlobalFromLocal (const math::Vector3 &_xyz) const
 Convert a Cartesian velocity vector in the local gazebo frame to a global Cartesian frame with components East, North, Up. More...
 
void SetElevationReference (double _elevation)
 Set reference elevation above sea level in meters. More...
 
void SetHeadingOffset (const math::Angle &_angle)
 Set heading angle offset for gazebo frame. More...
 
void SetLatitudeReference (const math::Angle &_angle)
 Set reference geodetic latitude. More...
 
void SetLongitudeReference (const math::Angle &_angle)
 Set reference longitude. More...
 
void SetSurfaceType (const SurfaceType &_type)
 Set SurfaceType for planetary surface model. More...
 
math::Vector3 SphericalFromLocal (const math::Vector3 &_xyz) const
 Convert a Cartesian position vector to geodetic coordinates. More...
 

Static Public Member Functions

static SurfaceType Convert (const std::string &_str)
 Convert a string to a SurfaceType. More...
 

Detailed Description

Convert spherical coordinates for planetary surfaces.

Member Enumeration Documentation

Unique identifiers for planetary surface models.

Enumerator
EARTH_WGS84 

Model of reference ellipsoid for earth, based on WGS 84 standard.

see wikipedia: World_Geodetic_System

Constructor & Destructor Documentation

gazebo::common::SphericalCoordinates::SphericalCoordinates ( )

Constructor.

gazebo::common::SphericalCoordinates::SphericalCoordinates ( const SurfaceType  _type)

Constructor with surface type input.

Parameters
[in]_typeSurfaceType specification.
gazebo::common::SphericalCoordinates::SphericalCoordinates ( const SurfaceType  _type,
const math::Angle _latitude,
const math::Angle _longitude,
double  _elevation,
const math::Angle _heading 
)

Constructor with surface type, angle, and elevation inputs.

Parameters
[in]_typeSurfaceType specification.
[in]_latitudeReference latitude.
[in]_longitudeReference longitude.
[in]_elevationReference elevation.
[in]_headingHeading offset.
gazebo::common::SphericalCoordinates::~SphericalCoordinates ( )

Destructor.

Member Function Documentation

static SurfaceType gazebo::common::SphericalCoordinates::Convert ( const std::string &  _str)
static

Convert a string to a SurfaceType.

Parameters
[in]_strString to convert.
Returns
Conversion to SurfaceType.
double gazebo::common::SphericalCoordinates::GetElevationReference ( ) const

Get reference elevation in meters.

Returns
Reference elevation.
math::Angle gazebo::common::SphericalCoordinates::GetHeadingOffset ( ) const

Get heading offset for gazebo reference frame, expressed as angle from East to gazebo x-axis, or equivalently from North to gazebo y-axis.

Returns
Heading offset of gazebo reference frame.
math::Angle gazebo::common::SphericalCoordinates::GetLatitudeReference ( ) const

Get reference geodetic latitude.

Returns
Reference geodetic latitude.
math::Angle gazebo::common::SphericalCoordinates::GetLongitudeReference ( ) const

Get reference longitude.

Returns
Reference longitude.
SurfaceType gazebo::common::SphericalCoordinates::GetSurfaceType ( ) const

Get SurfaceType currently in use.

Returns
Current SurfaceType value.
math::Vector3 gazebo::common::SphericalCoordinates::GlobalFromLocal ( const math::Vector3 _xyz) const

Convert a Cartesian velocity vector in the local gazebo frame to a global Cartesian frame with components East, North, Up.

Parameters
[in]_xyzCartesian vector in gazebo's world frame.
Returns
Rotated vector with components (x,y,z): (East, North, Up).
void gazebo::common::SphericalCoordinates::SetElevationReference ( double  _elevation)

Set reference elevation above sea level in meters.

Parameters
[in]_elevationReference elevation.
void gazebo::common::SphericalCoordinates::SetHeadingOffset ( const math::Angle _angle)

Set heading angle offset for gazebo frame.

Parameters
[in]_angleHeading offset for gazebo frame.
void gazebo::common::SphericalCoordinates::SetLatitudeReference ( const math::Angle _angle)

Set reference geodetic latitude.

Parameters
[in]_angleReference geodetic latitude.
void gazebo::common::SphericalCoordinates::SetLongitudeReference ( const math::Angle _angle)

Set reference longitude.

Parameters
[in]_angleReference longitude.
void gazebo::common::SphericalCoordinates::SetSurfaceType ( const SurfaceType _type)

Set SurfaceType for planetary surface model.

Parameters
[in]_typeSurfaceType value.
math::Vector3 gazebo::common::SphericalCoordinates::SphericalFromLocal ( const math::Vector3 _xyz) const

Convert a Cartesian position vector to geodetic coordinates.

Parameters
[in]_xyzCartesian position vector in gazebo's world frame.
Returns
Cooordinates: geodetic latitude (deg), longitude (deg), altitude above sea level (m).

The documentation for this class was generated from the following file: