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 } |
Unique identifiers for planetary surface models. More... | |
Public Member Functions | |
SphericalCoordinates () | |
Constructor. More... | |
SphericalCoordinates (const SphericalCoordinates &_sc) | |
Copy constructor. More... | |
SphericalCoordinates (const SurfaceType _type) | |
Constructor with surface type input. More... | |
SphericalCoordinates (const SurfaceType _type, const Angle &_latitude, const Angle &_longitude, const double _elevation, const Angle &_heading) | |
Constructor with surface type, angle, and elevation inputs. More... | |
~SphericalCoordinates () | |
Destructor. More... | |
double | ElevationReference () const |
Get reference elevation in meters. More... | |
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) More... | |
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. More... | |
Angle | LatitudeReference () const |
Get reference geodetic latitude. More... | |
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) More... | |
Vector3d | LocalFromSphericalPosition (const Vector3d &_latLonEle) const |
Convert a geodetic position vector to Cartesian coordinates. This performs a PositionTransform from SPHERICAL to LOCAL. More... | |
Angle | LongitudeReference () const |
Get reference longitude. More... | |
bool | operator!= (const SphericalCoordinates &_sc) const |
Inequality. More... | |
SphericalCoordinates & | operator= (const SphericalCoordinates &_sc) |
Assignment operator. More... | |
bool | operator== (const SphericalCoordinates &_sc) const |
Equality operator, result = this == _sc. More... | |
Vector3d | PositionTransform (const Vector3d &_pos, const CoordinateType &_in, const CoordinateType &_out) const |
Convert between positions in SPHERICAL/ECEF/LOCAL/GLOBAL frame Spherical coordinates use radians, while the other frames use meters. More... | |
void | SetElevationReference (const double _elevation) |
Set reference elevation above sea level in meters. More... | |
void | SetHeadingOffset (const Angle &_angle) |
Set heading angle offset for the frame. More... | |
void | SetLatitudeReference (const Angle &_angle) |
Set reference geodetic latitude. More... | |
void | SetLongitudeReference (const Angle &_angle) |
Set reference longitude. More... | |
void | SetSurface (const SurfaceType &_type) |
Set SurfaceType for planetary surface model. More... | |
Vector3d | SphericalFromLocalPosition (const Vector3d &_xyz) const |
Convert a Cartesian position vector to geodetic coordinates. This performs a PositionTransform from LOCAL to SPHERICAL. More... | |
SurfaceType | Surface () const |
Get SurfaceType currently in use. More... | |
void | UpdateTransformationMatrix () |
Update coordinate transformation matrix with reference location. More... | |
Vector3d | VelocityTransform (const Vector3d &_vel, const CoordinateType &_in, const CoordinateType &_out) const |
Convert between velocity in SPHERICAL/ECEF/LOCAL/GLOBAL frame Spherical coordinates use radians, while the other frames use meters. More... | |
Static Public Member Functions | |
static SurfaceType | Convert (const std::string &_str) |
Convert a string to a SurfaceType. Allowed values: ["EARTH_WGS84"]. More... | |
static std::string | Convert (SurfaceType _type) |
Convert a SurfaceType to a string. More... | |
static double | Distance (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. More... | |
Detailed Description
Convert spherical coordinates for planetary surfaces.
Member Enumeration Documentation
◆ CoordinateType
enum CoordinateType |
Unique identifiers for coordinate types.
◆ SurfaceType
enum SurfaceType |
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 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.
◆ SphericalCoordinates() [4/4]
SphericalCoordinates | ( | const SphericalCoordinates & | _sc | ) |
Copy constructor.
- Parameters
-
[in] _sc Spherical coordinates to copy.
◆ ~SphericalCoordinates()
~SphericalCoordinates | ( | ) |
Destructor.
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
◆ Distance()
|
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] _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()
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)
There's a known bug with this computation that can't be fixed on version 6 to avoid behaviour changes. Directly call VelocityTransform(_xyz, LOCAL2, GLOBAL)
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()
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.
◆ LocalFromSphericalPosition()
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 (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=()
SphericalCoordinates& operator= | ( | const SphericalCoordinates & | _sc | ) |
Assignment operator.
- Parameters
-
[in] _sc The spherical coordinates to copy from.
- Returns
- this
◆ 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()
Vector3d PositionTransform | ( | const Vector3d & | _pos, |
const CoordinateType & | _in, | ||
const CoordinateType & | _out | ||
) | const |
Convert between positions in SPHERICAL/ECEF/LOCAL/GLOBAL frame Spherical coordinates use radians, while the other frames use meters.
- Parameters
-
[in] _pos Position vector in frame defined by parameter _in [in] _in CoordinateType for input [in] _out CoordinateType for output
- Returns
- Transformed coordinate using cached origin.
◆ SetElevationReference()
void SetElevationReference | ( | const double | _elevation | ) |
Set reference elevation above sea level in meters.
- Parameters
-
[in] _elevation Reference elevation.
◆ SetHeadingOffset()
void SetHeadingOffset | ( | const Angle & | _angle | ) |
Set heading angle offset for the frame.
- Parameters
-
[in] _angle Heading offset for the frame.
◆ SetLatitudeReference()
void SetLatitudeReference | ( | const Angle & | _angle | ) |
Set reference geodetic latitude.
- Parameters
-
[in] _angle Reference geodetic latitude.
◆ SetLongitudeReference()
void SetLongitudeReference | ( | const Angle & | _angle | ) |
Set reference longitude.
- Parameters
-
[in] _angle Reference longitude.
◆ SetSurface()
void SetSurface | ( | const SurfaceType & | _type | ) |
Set SurfaceType for planetary surface model.
- Parameters
-
[in] _type SurfaceType value.
◆ SphericalFromLocalPosition()
Convert a Cartesian position vector to geodetic coordinates. This performs a PositionTransform
from LOCAL to SPHERICAL.
There's a known bug with this computation that can't be fixed on version 6 to avoid behaviour changes. Directly call PositionTransform(_xyz, LOCAL2, SPHERICAL)
for correct results. Note that PositionTransform
returns spherical coordinates in radians.
- 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.
◆ UpdateTransformationMatrix()
void UpdateTransformationMatrix | ( | ) |
Update coordinate transformation matrix with reference location.
◆ VelocityTransform()
Vector3d VelocityTransform | ( | const Vector3d & | _vel, |
const CoordinateType & | _in, | ||
const CoordinateType & | _out | ||
) | const |
Convert between velocity in SPHERICAL/ECEF/LOCAL/GLOBAL frame Spherical coordinates use radians, while the other frames use meters.
- 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
The documentation for this class was generated from the following file: