SphericalCoordinates Class Reference

Convert spherical coordinates for planetary surfaces. More...

#include <commmon/common.hh>

Public Types

enum  CoordinateType { SPHERICAL = 1, ECEF = 2, GLOBAL = 3, LOCAL = 4 }
 Unique identifiers for coordinate types. More...
 
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 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...
 
SurfaceType GetSurfaceType () const
 Get SurfaceType currently in use. 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::Vector3d LocalFromGlobal (const ignition::math::Vector3d &_xyz) const
 Convert a Cartesian vector with components East, North, Up to a local Gazebo cartesian frame vector XYZ. More...
 
ignition::math::Vector3d LocalFromSpherical (const ignition::math::Vector3d &_xyz) const
 Convert a geodetic position vector to Cartesian coordinates. More...
 
ignition::math::Angle LongitudeReference () const
 Get reference longitude. More...
 
ignition::math::Vector3d PositionTransform (const ignition::math::Vector3d &_pos, const CoordinateType &_in, const CoordinateType &_out) const
 Convert between positions in SPHERICAL/ECEF/LOCAL/GLOBAL frame. More...
 
void SetElevationReference (double _elevation)
 Set reference elevation above sea level in meters. More...
 
void SetHeadingOffset (const ignition::math::Angle &_angle)
 Set heading angle offset for gazebo frame. More...
 
void SetLatitudeReference (const ignition::math::Angle &_angle)
 Set reference geodetic latitude. More...
 
void SetLongitudeReference (const ignition::math::Angle &_angle)
 Set reference longitude. More...
 
void SetSurfaceType (const SurfaceType &_type)
 Set SurfaceType for planetary surface model. More...
 
ignition::math::Vector3d SphericalFromLocal (const ignition::math::Vector3d &_xyz) const
 Convert a Cartesian position vector to geodetic coordinates. More...
 
void UpdateTransformationMatrix ()
 Update coordinate transformation matrix with reference location. More...
 
ignition::math::Vector3d VelocityTransform (const ignition::math::Vector3d &_vel, const CoordinateType &_in, const CoordinateType &_out) const
 Convert between velocity in SPHERICAL/ECEF/LOCAL/GLOBAL frame. More...
 

Static Public Member Functions

static SurfaceType Convert (const std::string &_str)
 Convert a string to a SurfaceType. 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

§ CoordinateType

Unique identifiers for coordinate types.

Enumerator
SPHERICAL 

Latitude, Longitude and Altitude by SurfaceType.

ECEF 

Earth centered, earth fixed Cartesian.

GLOBAL 

Local tangent plane (East, North, Up)

LOCAL 

Heading-adjusted tangent plane (X, Y, Z)

§ SurfaceType

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

§ SphericalCoordinates() [1/3]

Constructor.

§ SphericalCoordinates() [2/3]

Constructor with surface type input.

Parameters
[in]_typeSurfaceType specification.

§ SphericalCoordinates() [3/3]

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.

§ ~SphericalCoordinates()

Destructor.

Member Function Documentation

§ Convert()

static SurfaceType Convert ( const std::string &  _str)
static

Convert a string to a SurfaceType.

Parameters
[in]_strString to convert.
Returns
Conversion to SurfaceType.

§ Distance()

static double 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.

§ GetElevationReference()

double GetElevationReference ( ) const

Get reference elevation in meters.

Returns
Reference elevation.

§ GetSurfaceType()

SurfaceType GetSurfaceType ( ) const

Get SurfaceType currently in use.

Returns
Current SurfaceType value.

§ GlobalFromLocal()

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.

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

§ HeadingOffset()

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.

Returns
Heading offset of gazebo reference frame.

§ LatitudeReference()

ignition::math::Angle LatitudeReference ( ) const

Get reference geodetic latitude.

Returns
Reference geodetic latitude.

§ LocalFromGlobal()

ignition::math::Vector3d LocalFromGlobal ( const ignition::math::Vector3d &  _xyz) const

Convert a Cartesian vector with components East, North, Up to a local Gazebo cartesian frame vector XYZ.

Parameters
[in]Vectorwith components (x,y,z): (East, North, Up).
Returns
Cartesian vector in Gazebo's world frame.

§ LocalFromSpherical()

ignition::math::Vector3d LocalFromSpherical ( const ignition::math::Vector3d &  _xyz) const

Convert a geodetic position vector to Cartesian coordinates.

Parameters
[in]_xyzGeodetic position in the planetary frame of reference
Returns
Cartesian vector in Gazebo's world frame

§ LongitudeReference()

ignition::math::Angle LongitudeReference ( ) const

Get reference longitude.

Returns
Reference longitude.

§ PositionTransform()

ignition::math::Vector3d PositionTransform ( const ignition::math::Vector3d &  _pos,
const CoordinateType _in,
const CoordinateType _out 
) const

Convert between positions in SPHERICAL/ECEF/LOCAL/GLOBAL frame.

Parameters
[in]_posPosition vector in frame defined by parameter _in
[in]_inCoordinateType for input
[in]_outCoordinateType for output
Returns
Transformed coordinate using cached orgin

§ SetElevationReference()

void SetElevationReference ( double  _elevation)

Set reference elevation above sea level in meters.

Parameters
[in]_elevationReference elevation.

§ SetHeadingOffset()

void SetHeadingOffset ( const ignition::math::Angle &  _angle)

Set heading angle offset for gazebo frame.

Parameters
[in]_angleHeading offset for gazebo frame.

§ SetLatitudeReference()

void SetLatitudeReference ( const ignition::math::Angle &  _angle)

Set reference geodetic latitude.

Parameters
[in]_angleReference geodetic latitude.

§ SetLongitudeReference()

void SetLongitudeReference ( const ignition::math::Angle &  _angle)

Set reference longitude.

Parameters
[in]_angleReference longitude.

§ SetSurfaceType()

void SetSurfaceType ( const SurfaceType _type)

Set SurfaceType for planetary surface model.

Parameters
[in]_typeSurfaceType value.

§ SphericalFromLocal()

ignition::math::Vector3d 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).

§ UpdateTransformationMatrix()

void UpdateTransformationMatrix ( )

Update coordinate transformation matrix with reference location.

§ VelocityTransform()

ignition::math::Vector3d VelocityTransform ( const ignition::math::Vector3d &  _vel,
const CoordinateType _in,
const CoordinateType _out 
) const

Convert between velocity in SPHERICAL/ECEF/LOCAL/GLOBAL frame.

Parameters
[in]_posVelocity vector in frame defined by parameter _in
[in]_inCoordinateType for input
[in]_outCoordinateType for output
Returns
Transformed velocity vector

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