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... | |
Convert spherical coordinates for planetary surfaces.
gazebo::common::SphericalCoordinates::SphericalCoordinates | ( | ) |
Constructor.
gazebo::common::SphericalCoordinates::SphericalCoordinates | ( | const SurfaceType | _type | ) |
Constructor with surface type input.
[in] | _type | SurfaceType 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.
[in] | _type | SurfaceType specification. |
[in] | _latitude | Reference latitude. |
[in] | _longitude | Reference longitude. |
[in] | _elevation | Reference elevation. |
[in] | _heading | Heading offset. |
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.
[in] | _type | SurfaceType specification. |
[in] | _latitude | Reference latitude. |
[in] | _longitude | Reference longitude. |
[in] | _elevation | Reference elevation. |
[in] | _heading | Heading offset. |
gazebo::common::SphericalCoordinates::~SphericalCoordinates | ( | ) |
Destructor.
|
static |
Convert a string to a SurfaceType.
[in] | _str | String to convert. |
|
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.
[in] | _latA | Latitude of point A. |
[in] | _longA | Longitude of point A. |
[in] | _latB | Latitude of point B. |
[in] | _longB | Longitude of point B. |
|
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.
[in] | _latA | Latitude of point A. |
[in] | _longA | Longitude of point A. |
[in] | _latB | Latitude of point B. |
[in] | _longB | Longitude of point B. |
double gazebo::common::SphericalCoordinates::GetElevationReference | ( | ) | const |
Get reference elevation in meters.
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.
math::Angle gazebo::common::SphericalCoordinates::GetLatitudeReference | ( | ) | const |
Get reference geodetic latitude.
math::Angle gazebo::common::SphericalCoordinates::GetLongitudeReference | ( | ) | const |
Get reference longitude.
SurfaceType gazebo::common::SphericalCoordinates::GetSurfaceType | ( | ) | const |
Get SurfaceType currently in use.
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.
[in] | _xyz | Cartesian vector in gazebo's world frame. |
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.
[in] | _xyz | Cartesian vector in gazebo's world frame. |
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.
ignition::math::Angle gazebo::common::SphericalCoordinates::LatitudeReference | ( | ) | const |
Get reference geodetic latitude.
ignition::math::Angle gazebo::common::SphericalCoordinates::LongitudeReference | ( | ) | const |
Get reference longitude.
void gazebo::common::SphericalCoordinates::SetElevationReference | ( | double | _elevation | ) |
Set reference elevation above sea level in meters.
[in] | _elevation | Reference elevation. |
void gazebo::common::SphericalCoordinates::SetHeadingOffset | ( | const math::Angle & | _angle | ) |
Set heading angle offset for gazebo frame.
[in] | _angle | Heading offset for gazebo frame. |
void gazebo::common::SphericalCoordinates::SetHeadingOffset | ( | const ignition::math::Angle & | _angle | ) |
Set heading angle offset for gazebo frame.
[in] | _angle | Heading offset for gazebo frame. |
void gazebo::common::SphericalCoordinates::SetLatitudeReference | ( | const math::Angle & | _angle | ) |
Set reference geodetic latitude.
[in] | _angle | Reference geodetic latitude. |
void gazebo::common::SphericalCoordinates::SetLatitudeReference | ( | const ignition::math::Angle & | _angle | ) |
Set reference geodetic latitude.
[in] | _angle | Reference geodetic latitude. |
void gazebo::common::SphericalCoordinates::SetLongitudeReference | ( | const math::Angle & | _angle | ) |
Set reference longitude.
[in] | _angle | Reference longitude. |
void gazebo::common::SphericalCoordinates::SetLongitudeReference | ( | const ignition::math::Angle & | _angle | ) |
Set reference longitude.
[in] | _angle | Reference longitude. |
void gazebo::common::SphericalCoordinates::SetSurfaceType | ( | const SurfaceType & | _type | ) |
Set SurfaceType for planetary surface model.
[in] | _type | SurfaceType value. |
math::Vector3 gazebo::common::SphericalCoordinates::SphericalFromLocal | ( | const math::Vector3 & | _xyz | ) | const |
Convert a Cartesian position vector to geodetic coordinates.
[in] | _xyz | Cartesian position vector in gazebo's world frame. |
ignition::math::Vector3d gazebo::common::SphericalCoordinates::SphericalFromLocal | ( | const ignition::math::Vector3d & | _xyz | ) | const |
Convert a Cartesian position vector to geodetic coordinates.
[in] | _xyz | Cartesian position vector in gazebo's world frame. |