Common getter functions for the ETSI ITS Common Data Dictionary (CDD) v1.3.1 and v2.1.1. More...
#include <array>#include <cmath>#include <cstdint>#include <GeographicLib/UTMUPS.hpp>

Go to the source code of this file.
Functions | |
| std::array< double, 4 > | CovMatrixFromConfidenceEllipse (double semi_major, double semi_minor, double major_orientation, const double object_heading) |
| Convert the confidence ellipse to a covariance matrix. More... | |
| double | getAltitude (const Altitude &altitude) |
| Get the Altitude value. More... | |
| template<typename Heading > | |
| double | getHeadingCDD (const Heading &heading) |
| Get the Heading value. More... | |
| template<typename Heading > | |
| double | getHeadingConfidenceCDD (const Heading &heading) |
| Get the Heading value. More... | |
| double | getLatitude (const Latitude &latitude) |
| Get the Latitude value. More... | |
| double | getLongitude (const Longitude &longitude) |
| Get the Longitude value. More... | |
| template<typename PosConfidenceEllipse > | |
| std::tuple< double, double, double > | getPosConfidenceEllipse (const PosConfidenceEllipse &position_confidence_ellipse) |
| Extract major axis length, minor axis length and orientation from the given position confidence ellipse. More... | |
| template<typename PosConfidenceEllipse > | |
| std::array< double, 4 > | getPosConfidenceEllipse (const PosConfidenceEllipse &position_confidence_ellipse, const double object_heading) |
| Get the covariance matrix of the position confidence ellipse. More... | |
| template<typename SemiAxisLength > | |
| double | getSemiAxis (const SemiAxisLength &semi_axis_length) |
| Get the Semi Axis object. More... | |
| double | getSpeed (const Speed &speed) |
| Get the vehicle speed. More... | |
| double | getSpeedConfidence (const Speed &speed) |
| Get the Speed Confidence. More... | |
| uint32_t | getStationID (const ItsPduHeader &header) |
| Get the StationID of ItsPduHeader. More... | |
| template<typename T > | |
| gm::PointStamped | getUTMPosition (const T &reference_position, int &zone, bool &northp) |
| Get the UTM Position defined by the given ReferencePosition. More... | |
| template<typename PosConfidenceEllipse > | |
| std::array< double, 4 > | getWGSPosConfidenceEllipse (const PosConfidenceEllipse &position_confidence_ellipse) |
| Get the covariance matrix of the position confidence ellipse. More... | |
| std::array< double, 4 > | WGSCovMatrixFromConfidenceEllipse (double semi_major, double semi_minor, double major_orientation) |
| Convert the confidence ellipse to a covariance matrix. More... | |
Common getter functions for the ETSI ITS Common Data Dictionary (CDD) v1.3.1 and v2.1.1.
Definition in file cdd_getters_common.h.
|
inline |
Convert the confidence ellipse to a covariance matrix.
Note that the major_orientation is given in degrees, while the object_heading is given in radians!
| semi_major | Semi major axis length in meters |
| semi_minor | Semi minor axis length in meters |
| major_orientation | Orientation of the major axis in degrees, relative to WGS84 |
| object_heading | object heading in radians, relative to WGS84 |
Definition at line 181 of file cdd_getters_common.h.
|
inline |
Get the Altitude value.
| altitude | to get the Altitude value from |
Definition at line 70 of file cdd_getters_common.h.
|
inline |
Get the Heading value.
0.0° equals WGS84 North, 90.0° equals WGS84 East, 180.0° equals WGS84 South and 270.0° equals WGS84 West
| heading | to get the Heading value from |
Definition at line 131 of file cdd_getters_common.h.
|
inline |
Get the Heading value.
0.0° equals WGS84 North, 90.0° equals WGS84 East, 180.0° equals WGS84 South and 270.0° equals WGS84 West
| heading | to get the Heading standard deviation from |
Definition at line 142 of file cdd_getters_common.h.
|
inline |
Get the Latitude value.
| latitude | to get the Latitude value from |
Definition at line 54 of file cdd_getters_common.h.
|
inline |
Get the Longitude value.
| longitude | to get the Longitude value from |
Definition at line 62 of file cdd_getters_common.h.
|
inline |
Extract major axis length, minor axis length and orientation from the given position confidence ellipse.
| position_confidence_ellipse | The position confidence ellipse to extract the values from |
Definition at line 162 of file cdd_getters_common.h.
|
inline |
Get the covariance matrix of the position confidence ellipse.
| position_confidence_ellipse | The position confidence ellipse to get the covariance matrix from |
| object_heading | The object heading in radians |
Definition at line 223 of file cdd_getters_common.h.
|
inline |
Get the Semi Axis object.
| semi_axis_length | The SemiAxisLength object to get the semi axis from |
Definition at line 151 of file cdd_getters_common.h.
|
inline |
Get the vehicle speed.
| speed | to get the speed value from |
Definition at line 78 of file cdd_getters_common.h.
|
inline |
Get the Speed Confidence.
| speed | to get the SpeedConfidence from |
Definition at line 86 of file cdd_getters_common.h.
|
inline |
Get the StationID of ItsPduHeader.
| header | ItsPduHeader to get the StationID value from |
Definition at line 46 of file cdd_getters_common.h.
|
inline |
Get the UTM Position defined by the given ReferencePosition.
The position is transformed into UTM by using GeographicLib::UTMUPS The altitude value is directly used as z-Coordinate
| [in] | reference_position | ReferencePosition or ReferencePositionWithConfidence to get the UTM Position from |
| [out] | zone | the UTM zone (zero means UPS) |
| [out] | northp | hemisphere (true means north, false means south) |
Definition at line 102 of file cdd_getters_common.h.
|
inline |
Get the covariance matrix of the position confidence ellipse.
| position_confidence_ellipse | The position confidence ellipse to get the covariance matrix from |
| object_heading | The object heading in radians |
Definition at line 236 of file cdd_getters_common.h.
|
inline |
Convert the confidence ellipse to a covariance matrix.
Note that the major_orientation is given in degrees, while the object_heading is given in radians!
| semi_major | Semi major axis length in meters |
| semi_minor | Semi minor axis length in meters |
| major_orientation | Orientation of the major axis in degrees, relative to WGS84 |
Definition at line 210 of file cdd_getters_common.h.