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) GAZEBO_DEPRECATED(6.0)
 Constructor with surface type, angle, and elevation inputs. More...
 
 SphericalCoordinates (const SurfaceType _type, const ignition::math::Angle &_latitude, const ignition::math::Angle &_longitude, double _elevation, const ignition::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 GAZEBO_DEPRECATED(6.0)
 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 GAZEBO_DEPRECATED(6.0)
 Get reference geodetic latitude. More...
 
math::Angle GetLongitudeReference () const GAZEBO_DEPRECATED(6.0)
 Get reference longitude. More...
 
SurfaceType GetSurfaceType () const
 Get SurfaceType currently in use. More...
 
math::Vector3 GlobalFromLocal (const math::Vector3 &_xyz) const GAZEBO_DEPRECATED(6.0)
 Convert a Cartesian velocity vector in the local gazebo frame to a global Cartesian frame with components East, North, Up. More...
 
ignition::math::Vector3d GlobalFromLocal (const ignition::math::Vector3d &_xyz) const
 Convert a Cartesian velocity vector in the local gazebo frame to a global Cartesian frame with components East, North, Up. More...
 
ignition::math::Angle HeadingOffset () 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...
 
ignition::math::Angle LatitudeReference () const
 Get reference geodetic latitude. More...
 
ignition::math::Angle LongitudeReference () const
 Get reference longitude. More...
 
void SetElevationReference (double _elevation)
 Set reference elevation above sea level in meters. More...
 
void SetHeadingOffset (const math::Angle &_angle) GAZEBO_DEPRECATED(6.0)
 Set heading angle offset for gazebo frame. More...
 
void SetHeadingOffset (const ignition::math::Angle &_angle)
 Set heading angle offset for gazebo frame. More...
 
void SetLatitudeReference (const math::Angle &_angle) GAZEBO_DEPRECATED(6.0)
 Set reference geodetic latitude. More...
 
void SetLatitudeReference (const ignition::math::Angle &_angle)
 Set reference geodetic latitude. More...
 
void SetLongitudeReference (const math::Angle &_angle) GAZEBO_DEPRECATED(6.0)
 Set reference longitude. More...
 
void SetLongitudeReference (const ignition::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 GAZEBO_DEPRECATED(6.0)
 Convert a Cartesian position vector to geodetic coordinates. More...
 
ignition::math::Vector3d SphericalFromLocal (const ignition::math::Vector3d &_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...
 
static double Distance (const math::Angle &_latA, const math::Angle &_lonA, const math::Angle &_latB, const math::Angle &_lonB) GAZEBO_DEPRECATED(6.0)
 Get the distance between two points expressed in geographic latitude and longitude. More...
 
static double Distance (const ignition::math::Angle &_latA, const ignition::math::Angle &_lonA, const ignition::math::Angle &_latB, const ignition::math::Angle &_lonB)
 Get the distance between two points expressed in geographic latitude and longitude. 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.
Deprecated:
See SphericalCoordinates constructor that accepts ignition::math::Angle objects.
gazebo::common::SphericalCoordinates::SphericalCoordinates ( const SurfaceType  _type,
const ignition::math::Angle &  _latitude,
const ignition::math::Angle &  _longitude,
double  _elevation,
const ignition::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.
static double gazebo::common::SphericalCoordinates::Distance ( const math::Angle _latA,
const math::Angle _lonA,
const math::Angle _latB,
const math::Angle _lonB 
)
static

Get the distance between two points expressed in geographic latitude and longitude.

It assumes that both points are at sea level. Example: _latA = 38.0016667 and _lonA = -123.0016667) represents the point with latitude 38d 0'6.00"N and longitude 123d 0'6.00"W.

Parameters
[in]_latALatitude of point A.
[in]_longALongitude of point A.
[in]_latBLatitude of point B.
[in]_longBLongitude of point B.
Returns
Distance in meters.
Deprecated:
See Distance() function that accepts ignition::math::Angle objects.
static double gazebo::common::SphericalCoordinates::Distance ( const ignition::math::Angle &  _latA,
const ignition::math::Angle &  _lonA,
const ignition::math::Angle &  _latB,
const ignition::math::Angle &  _lonB 
)
static

Get the distance between two points expressed in geographic latitude and longitude.

It assumes that both points are at sea level. Example: _latA = 38.0016667 and _lonA = -123.0016667) represents the point with latitude 38d 0'6.00"N and longitude 123d 0'6.00"W.

Parameters
[in]_latALatitude of point A.
[in]_longALongitude of point A.
[in]_latBLatitude of point B.
[in]_longBLongitude of point B.
Returns
Distance in meters.
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.
Deprecated:
See HeadingOffset() function that returns an ignition::math::Angle object.
math::Angle gazebo::common::SphericalCoordinates::GetLatitudeReference ( ) const

Get reference geodetic latitude.

Returns
Reference geodetic latitude.
Deprecated:
See LatitudeReference function that returns an ignition::math::Angle object.
math::Angle gazebo::common::SphericalCoordinates::GetLongitudeReference ( ) const

Get reference longitude.

Returns
Reference longitude.
Deprecated:
See LongitudeReference function that returns an ignition::math::Angle object.
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).
Deprecated:
See GlobalFromLocal function that use ignition::math::Vector3d objects.
ignition::math::Vector3d gazebo::common::SphericalCoordinates::GlobalFromLocal ( const ignition::math::Vector3d &  _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).
ignition::math::Angle gazebo::common::SphericalCoordinates::HeadingOffset ( ) 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.
ignition::math::Angle gazebo::common::SphericalCoordinates::LatitudeReference ( ) const

Get reference geodetic latitude.

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

Get reference longitude.

Returns
Reference longitude.
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.
Deprecated:
See SetHeadingOffset function that accepts an ignition::math::Angle object.
void gazebo::common::SphericalCoordinates::SetHeadingOffset ( const ignition::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.
Deprecated:
See SetLatitudeReference function that accepts an ignition::math::Angle object.
void gazebo::common::SphericalCoordinates::SetLatitudeReference ( const ignition::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.
Deprecated:
See SetLongitudeReference function that accepts an ignition::math::Angle object.
void gazebo::common::SphericalCoordinates::SetLongitudeReference ( const ignition::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).
Deprecated:
See SphericalFromLocal function that use ignition::math::Vector3d objects.
ignition::math::Vector3d gazebo::common::SphericalCoordinates::SphericalFromLocal ( const ignition::math::Vector3d &  _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: