Convert spherical coordinates for planetary surfaces. More...
#include <SphericalCoordinates.hh>
Public Types | |
enum | CoordinateType { SPHERICAL = 1 , ECEF = 2 , GLOBAL = 3 , LOCAL = 4 , LOCAL2 = 5 } |
Unique identifiers for coordinate types. More... | |
enum | SurfaceType { EARTH_WGS84 = 1 , MOON_SCS = 2 , CUSTOM_SURFACE = 10 } |
Unique identifiers for planetary surface models. More... | |
Public Member Functions | |
SphericalCoordinates () | |
Constructor. | |
SphericalCoordinates (const SurfaceType _type) | |
Constructor with surface type input. | |
SphericalCoordinates (const SurfaceType _type, const Angle &_latitude, const Angle &_longitude, const double _elevation, const Angle &_heading) | |
Constructor with surface type, angle, and elevation inputs. | |
SphericalCoordinates (const SurfaceType _type, const double _axisEquatorial, const double _axisPolar) | |
Constructor with surface type input and properties input. To be used for CUSTOM_SURFACE. | |
double | DistanceBetweenPoints (const Angle &_latA, const Angle &_lonA, const Angle &_latB, const Angle &_lonB) |
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. This is different from the deprecated static Distance() method as it takes into account the set surface's radius. | |
double | ElevationReference () const |
Get reference elevation in meters. | |
std::optional< math::CoordinateVector3 > | GlobalFromLocalVelocity (const CoordinateVector3 &_xyz) const |
Convert a Cartesian velocity vector in the local frame to a global Cartesian frame with components East, North, Up. This is a wrapper around VelocityTransform(_xyz, LOCAL, GLOBAL) | |
Vector3d | GlobalFromLocalVelocity (const Vector3d &_xyz) const |
Convert a Cartesian velocity vector in the local frame to a global Cartesian frame with components East, North, Up. This is a wrapper around VelocityTransform(_xyz, LOCAL, GLOBAL) | |
Angle | HeadingOffset () const |
Get heading offset for the reference frame, expressed as angle from East to x-axis, or equivalently from North to y-axis. | |
Angle | LatitudeReference () const |
Get reference geodetic latitude. | |
std::optional< math::CoordinateVector3 > | LocalFromGlobalVelocity (const CoordinateVector3 &_xyz) const |
Convert a Cartesian velocity vector with components East, North, Up to a local cartesian frame vector XYZ. This is a wrapper around VelocityTransform(_xyz, GLOBAL, LOCAL) | |
Vector3d | LocalFromGlobalVelocity (const Vector3d &_xyz) const |
Convert a Cartesian velocity vector with components East, North, Up to a local cartesian frame vector XYZ. This is a wrapper around VelocityTransform(_xyz, GLOBAL, LOCAL) | |
std::optional< math::CoordinateVector3 > | LocalFromSphericalPosition (const CoordinateVector3 &_latLonEle) const |
Convert a geodetic position vector to Cartesian coordinates. This performs a PositionTransform from SPHERICAL to LOCAL. | |
Vector3d | LocalFromSphericalPosition (const Vector3d &_latLonEle) const |
Convert a geodetic position vector to Cartesian coordinates. This performs a PositionTransform from SPHERICAL to LOCAL. | |
Angle | LongitudeReference () const |
Get reference longitude. | |
bool | operator!= (const SphericalCoordinates &_sc) const |
Inequality. | |
bool | operator== (const SphericalCoordinates &_sc) const |
Equality operator, result = this == _sc. | |
std::optional< CoordinateVector3 > | PositionTransform (const CoordinateVector3 &_pos, const CoordinateType &_in, const CoordinateType &_out) const |
Convert between positions in SPHERICAL/ECEF/LOCAL/GLOBAL frame using the cached reference point. | |
Vector3d | PositionTransform (const Vector3d &_pos, const CoordinateType &_in, const CoordinateType &_out) const |
Convert between positions in SPHERICAL/ECEF/LOCAL/GLOBAL frame using the reference point. | |
void | SetElevationReference (const double _elevation) |
Set reference elevation above sea level in meters. | |
void | SetHeadingOffset (const Angle &_angle) |
Set heading angle offset for the frame. | |
void | SetLatitudeReference (const Angle &_angle) |
Set reference geodetic latitude. | |
void | SetLongitudeReference (const Angle &_angle) |
Set reference longitude. | |
void | SetSurface (const SurfaceType &_type) |
Set SurfaceType for planetary surface model. | |
void | SetSurface (const SurfaceType &_type, const double _axisEquatorial, const double _axisPolar) |
Set SurfaceType for planetary surface model with custom ellipsoid properties. | |
std::optional< math::CoordinateVector3 > | SphericalFromLocalPosition (const CoordinateVector3 &_xyz) const |
Convert a Cartesian position vector to geodetic coordinates. This performs a PositionTransform from LOCAL to SPHERICAL. | |
Vector3d | SphericalFromLocalPosition (const Vector3d &_xyz) const |
Convert a Cartesian position vector to geodetic coordinates. This performs a PositionTransform from LOCAL to SPHERICAL. | |
SurfaceType | Surface () const |
Get SurfaceType currently in use. | |
double | SurfaceAxisEquatorial () const |
Get the major axis of the surface. | |
double | SurfaceAxisPolar () const |
Get the minor axis of the surface. | |
double | SurfaceFlattening () const |
Get the flattening of the surface. | |
double | SurfaceRadius () const |
Get the radius of the surface. | |
void | UpdateTransformationMatrix () |
Update coordinate transformation matrix with reference location. | |
std::optional< CoordinateVector3 > | VelocityTransform (const CoordinateVector3 &_vel, const CoordinateType &_in, const CoordinateType &_out) const |
Convert between velocity in ECEF/LOCAL/GLOBAL frame. | |
Vector3d | VelocityTransform (const Vector3d &_vel, const CoordinateType &_in, const CoordinateType &_out) const |
Convert between velocity in ECEF/LOCAL/GLOBAL frame using the cached reference point. | |
Static Public Member Functions | |
static SurfaceType | Convert (const std::string &_str) |
Convert a string to a SurfaceType. Allowed values: ["EARTH_WGS84"]. | |
static std::string | Convert (SurfaceType _type) |
Convert a SurfaceType to a string. | |
static double | DistanceWGS84 (const Angle &_latA, const Angle &_lonA, const Angle &_latB, const Angle &_lonB) |
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. This method assumes that the surface model is EARTH_WGS84. | |
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) |
LOCAL2 | Heading-adjusted tangent plane (X, Y, Z)
|
◆ SurfaceType
Unique identifiers for planetary surface models.
Constructor & Destructor Documentation
◆ SphericalCoordinates() [1/4]
Constructor.
◆ SphericalCoordinates() [2/4]
|
explicit |
Constructor with surface type input.
- Parameters
-
[in] _type SurfaceType specification.
◆ SphericalCoordinates() [3/4]
SphericalCoordinates | ( | const SurfaceType | _type, |
const double | _axisEquatorial, | ||
const double | _axisPolar | ||
) |
Constructor with surface type input and properties input. To be used for CUSTOM_SURFACE.
- Parameters
-
[in] _type SurfaceType specification. [in] _axisEquatorial Semi major axis of the surface. [in] _axisPolar Semi minor axis of the surface.
◆ SphericalCoordinates() [4/4]
SphericalCoordinates | ( | const SurfaceType | _type, |
const Angle & | _latitude, | ||
const Angle & | _longitude, | ||
const double | _elevation, | ||
const Angle & | _heading | ||
) |
Constructor with surface type, angle, and elevation inputs.
- Parameters
-
[in] _type SurfaceType specification. [in] _latitude Reference latitude. [in] _longitude Reference longitude. [in] _elevation Reference elevation. [in] _heading Heading offset.
Member Function Documentation
◆ Convert() [1/2]
|
static |
Convert a string to a SurfaceType. Allowed values: ["EARTH_WGS84"].
- Parameters
-
[in] _str String to convert.
- Returns
- Conversion to SurfaceType.
◆ Convert() [2/2]
|
static |
Convert a SurfaceType to a string.
- Parameters
-
[in] _type Surface type
- Returns
- Type as string
◆ DistanceBetweenPoints()
double DistanceBetweenPoints | ( | const Angle & | _latA, |
const Angle & | _lonA, | ||
const Angle & | _latB, | ||
const Angle & | _lonB | ||
) |
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. This is different from the deprecated static Distance() method as it takes into account the set surface's radius.
- Parameters
-
[in] _latA Latitude of point A. [in] _lonA Longitude of point A. [in] _latB Latitude of point B. [in] _lonB Longitude of point B.
- Returns
- Distance in meters.
◆ DistanceWGS84()
|
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. This method assumes that the surface model is EARTH_WGS84.
- Parameters
-
[in] _latA Latitude of point A. [in] _lonA Longitude of point A. [in] _latB Latitude of point B. [in] _lonB Longitude of point B.
- Returns
- Distance in meters.
◆ ElevationReference()
double ElevationReference | ( | ) | const |
Get reference elevation in meters.
- Returns
- Reference elevation.
◆ GlobalFromLocalVelocity() [1/2]
std::optional< math::CoordinateVector3 > GlobalFromLocalVelocity | ( | const CoordinateVector3 & | _xyz | ) | const |
Convert a Cartesian velocity vector in the local frame to a global Cartesian frame with components East, North, Up. This is a wrapper around VelocityTransform(_xyz, LOCAL, GLOBAL)
- Parameters
-
[in] _xyz Cartesian velocity vector in the heading-adjusted world frame.
- Returns
- Rotated vector with components (x,y,z): (East, North, Up).
◆ GlobalFromLocalVelocity() [2/2]
Convert a Cartesian velocity vector in the local frame to a global Cartesian frame with components East, North, Up. This is a wrapper around VelocityTransform(_xyz, LOCAL, GLOBAL)
- Deprecated:
- There's a known bug with this computation that can't be fixed until Gazebo 8 to avoid behaviour changes. Call
GlobalFromLocalVelocity(CoordinateVector3)
for correct results.
- Parameters
-
[in] _xyz Cartesian velocity vector in the heading-adjusted world frame.
- Returns
- Rotated vector with components (x,y,z): (East, North, Up).
◆ HeadingOffset()
Angle HeadingOffset | ( | ) | const |
Get heading offset for the reference frame, expressed as angle from East to x-axis, or equivalently from North to y-axis.
- Returns
- Heading offset of reference frame.
◆ LatitudeReference()
Angle LatitudeReference | ( | ) | const |
Get reference geodetic latitude.
- Returns
- Reference geodetic latitude.
◆ LocalFromGlobalVelocity() [1/2]
std::optional< math::CoordinateVector3 > LocalFromGlobalVelocity | ( | const CoordinateVector3 & | _xyz | ) | const |
Convert a Cartesian velocity vector with components East, North, Up to a local cartesian frame vector XYZ. This is a wrapper around VelocityTransform(_xyz, GLOBAL, LOCAL)
- Parameters
-
[in] _xyz Vector with components (x,y,z): (East, North, Up).
- Returns
- Cartesian vector in the world frame.
◆ LocalFromGlobalVelocity() [2/2]
Convert a Cartesian velocity vector with components East, North, Up to a local cartesian frame vector XYZ. This is a wrapper around VelocityTransform(_xyz, GLOBAL, LOCAL)
- Deprecated:
- Use
LocalFromSphericalPosition(CoordinateVector3)
instead.
- Parameters
-
[in] _xyz Vector with components (x,y,z): (East, North, Up).
- Returns
- Cartesian vector in the world frame.
◆ LocalFromSphericalPosition() [1/2]
std::optional< math::CoordinateVector3 > LocalFromSphericalPosition | ( | const CoordinateVector3 & | _latLonEle | ) | const |
Convert a geodetic position vector to Cartesian coordinates. This performs a PositionTransform
from SPHERICAL to LOCAL.
- Parameters
-
[in] _latLonEle Geodetic position in the planetary frame of reference. X: latitude, Y: longitude, Z: altitude.
- Returns
- Cartesian position vector in the heading-adjusted world frame.
◆ LocalFromSphericalPosition() [2/2]
Convert a geodetic position vector to Cartesian coordinates. This performs a PositionTransform
from SPHERICAL to LOCAL.
- Deprecated:
- Use
LocalFromSphericalPosition(CoordinateVector3)
instead.
- Parameters
-
[in] _latLonEle Geodetic position in the planetary frame of reference. X: latitude (deg), Y: longitude (deg), X: altitude.
- Returns
- Cartesian position vector in the heading-adjusted world frame.
◆ LongitudeReference()
Angle LongitudeReference | ( | ) | const |
Get reference longitude.
- Returns
- Reference longitude.
◆ operator!=()
bool operator!= | ( | const SphericalCoordinates & | _sc | ) | const |
Inequality.
- Parameters
-
[in] _sc Spherical coordinates to check for inequality
- Returns
- true if this != _sc
◆ operator==()
bool operator== | ( | const SphericalCoordinates & | _sc | ) | const |
Equality operator, result = this == _sc.
- Parameters
-
[in] _sc Spherical coordinates to check for equality
- Returns
- true if this == _sc
◆ PositionTransform() [1/2]
std::optional< CoordinateVector3 > PositionTransform | ( | const CoordinateVector3 & | _pos, |
const CoordinateType & | _in, | ||
const CoordinateType & | _out | ||
) | const |
Convert between positions in SPHERICAL/ECEF/LOCAL/GLOBAL frame using the cached reference point.
- Parameters
-
[in] _pos Position vector in frame defined by parameter _in [in] _in CoordinateType for input [in] _out CoordinateType for output
- Returns
- Transformed coordinates (if the transformation succeeded).
◆ PositionTransform() [2/2]
Vector3d PositionTransform | ( | const Vector3d & | _pos, |
const CoordinateType & | _in, | ||
const CoordinateType & | _out | ||
) | const |
Convert between positions in SPHERICAL/ECEF/LOCAL/GLOBAL frame using the reference point.
- Deprecated:
- To keep compatibility with Gazebo 7 and earlier, this function returns incorrect result for LOCAL->SPHERICAL and LOCAL->GLOBAL cases. Preferably, switch to using
PositionTransform(CoordinateVector3, ..., LOCAL)
which yields correct results. If you need to use this deprecated overload, use coordinate type LOCAL2 to get the correct result.
- Parameters
-
[in] _pos Position vector in frame defined by parameter _in. If it is spherical, it has to be in radians. [in] _in CoordinateType for input [in] _out CoordinateType for output
- Returns
- Transformed coordinate using cached origin. Spherical coordinates will be in radians. In case of error,
_pos
is returned unchanged.
◆ SetElevationReference()
Set reference elevation above sea level in meters.
- Parameters
-
[in] _elevation Reference elevation.
◆ SetHeadingOffset()
Set heading angle offset for the frame.
- Parameters
-
[in] _angle Heading offset for the frame.
◆ SetLatitudeReference()
Set reference geodetic latitude.
- Parameters
-
[in] _angle Reference geodetic latitude.
◆ SetLongitudeReference()
Set reference longitude.
- Parameters
-
[in] _angle Reference longitude.
◆ SetSurface() [1/2]
void SetSurface | ( | const SurfaceType & | _type | ) |
Set SurfaceType for planetary surface model.
- Parameters
-
[in] _type SurfaceType value.
◆ SetSurface() [2/2]
void SetSurface | ( | const SurfaceType & | _type, |
const double | _axisEquatorial, | ||
const double | _axisPolar | ||
) |
Set SurfaceType for planetary surface model with custom ellipsoid properties.
- Parameters
-
[in] _type SurfaceType value. [in] _axisEquatorial Equatorial axis of the surface. [in] _axisPolar Polar axis of the surface.
◆ SphericalFromLocalPosition() [1/2]
std::optional< math::CoordinateVector3 > SphericalFromLocalPosition | ( | const CoordinateVector3 & | _xyz | ) | const |
Convert a Cartesian position vector to geodetic coordinates. This performs a PositionTransform
from LOCAL to SPHERICAL.
- Parameters
-
[in] _xyz Cartesian position vector in the heading-adjusted world frame.
- Returns
- Cooordinates: geodetic latitude, longitude, altitude above sea level.
◆ SphericalFromLocalPosition() [2/2]
Convert a Cartesian position vector to geodetic coordinates. This performs a PositionTransform
from LOCAL to SPHERICAL.
- Deprecated:
- There's a known bug with this computation that can't be fixed until Gazebo 8 to avoid behaviour changes. Call
SphericalFromLocalPosition(CoordinateVector3)
for correct results.
- Parameters
-
[in] _xyz Cartesian position vector in the heading-adjusted world frame.
- Returns
- Cooordinates: geodetic latitude (deg), longitude (deg), altitude above sea level (m).
◆ Surface()
SurfaceType Surface | ( | ) | const |
Get SurfaceType currently in use.
- Returns
- Current SurfaceType value.
◆ SurfaceAxisEquatorial()
double SurfaceAxisEquatorial | ( | ) | const |
Get the major axis of the surface.
- Returns
- Equatorial axis of the surface in use.
◆ SurfaceAxisPolar()
double SurfaceAxisPolar | ( | ) | const |
Get the minor axis of the surface.
- Returns
- Polar axis of the surface in use.
◆ SurfaceFlattening()
double SurfaceFlattening | ( | ) | const |
Get the flattening of the surface.
- Returns
- Flattening parameter of the surface in use.
◆ SurfaceRadius()
double SurfaceRadius | ( | ) | const |
Get the radius of the surface.
- Returns
- radius of the surface in use.
◆ UpdateTransformationMatrix()
void UpdateTransformationMatrix | ( | ) |
Update coordinate transformation matrix with reference location.
◆ VelocityTransform() [1/2]
std::optional< CoordinateVector3 > VelocityTransform | ( | const CoordinateVector3 & | _vel, |
const CoordinateType & | _in, | ||
const CoordinateType & | _out | ||
) | const |
Convert between velocity in ECEF/LOCAL/GLOBAL frame.
- Note
- Spherical coordinates are not supported.
- Parameters
-
[in] _vel Velocity vector in frame defined by parameter _in [in] _in CoordinateType for input [in] _out CoordinateType for output
- Returns
- Transformed velocity vector (if the transformation succeeded).
◆ VelocityTransform() [2/2]
Vector3d VelocityTransform | ( | const Vector3d & | _vel, |
const CoordinateType & | _in, | ||
const CoordinateType & | _out | ||
) | const |
Convert between velocity in ECEF/LOCAL/GLOBAL frame using the cached reference point.
- Note
- Spherical coordinates are not supported.
- Deprecated:
- To keep compatibility with Gazebo 7 and earlier, this function returns incorrect result for LOCAL->SPHERICAL and LOCAL->GLOBAL cases. Preferably, switch to using
VelocityTransform(CoordinateVector3, ..., LOCAL)
which yields correct results. If you need to use this deprecated overload, use coordinate type LOCAL2 to get the correct result.
- Parameters
-
[in] _vel Velocity vector in frame defined by parameter _in [in] _in CoordinateType for input [in] _out CoordinateType for output
- Returns
- Transformed velocity vector. In case of error,
_vel
is returned unchanged.
The documentation for this class was generated from the following file: