Functions
cdd_setters_common.h File Reference

Common setter functions for the ETSI ITS Common Data Dictionary (CDD) v1.3.1 and v2.1.1. More...

#include <etsi_its_msgs_utils/impl/checks.h>
#include <etsi_its_msgs_utils/impl/constants.h>
#include <GeographicLib/UTMUPS.hpp>
#include <array>
#include <cmath>
#include <cstdint>
#include <cstring>
#include <type_traits>
Include dependency graph for cdd_setters_common.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Functions

std::tuple< double, double, double > confidenceEllipseFromCovMatrix (const std::array< double, 4 > &covariance_matrix, const double object_heading)
 Gets the values needed to set a confidence ellipse from a covariance matrix. More...
 
std::tuple< double, double, double > confidenceEllipseFromWGSCovMatrix (const std::array< double, 4 > &covariance_matrix)
 Gets the values needed to set a confidence ellipse from a covariance matrix. More...
 
template<typename AccelerationConfidence >
void setAccelerationConfidence (AccelerationConfidence &accel_confidence, const double value)
 Set the Acceleration Confidence object. More...
 
void setAltitude (Altitude &altitude, const double value)
 Set the Altitude object. More...
 
void setAltitudeValue (AltitudeValue &altitude, const double value)
 Set the AltitudeValue object. More...
 
template<typename T >
void setFromUTMPosition (T &reference_position, const gm::PointStamped &utm_position, const int zone, const bool northp)
 Set the ReferencePosition from a given UTM-Position. More...
 
template<typename Heading , typename HeadingConfidence = decltype(Heading::heading_confidence)>
void setHeadingCDD (Heading &heading, const double value, double confidence=std::numeric_limits< double >::infinity())
 Set the Heading object. More...
 
template<typename HeadingConfidence >
void setHeadingConfidence (HeadingConfidence &heading_confidence, const double value)
 Set the Heading Confidence object. More...
 
template<typename HeadingValue >
void setHeadingValue (HeadingValue &heading, const double value)
 Set the HeadingValue object. More...
 
void setLatitude (Latitude &latitude, const double deg)
 Set the Latitude object. More...
 
void setLongitude (Longitude &longitude, const double deg)
 Set the Longitude object. More...
 
template<typename PosConfidenceEllipse >
void setPosConfidenceEllipse (PosConfidenceEllipse &position_confidence_ellipse, const double semi_major_axis, const double semi_minor_axis, const double orientation)
 Set the Pos Confidence Ellipse object. More...
 
template<typename PosConfidenceEllipse >
void setPosConfidenceEllipse (PosConfidenceEllipse &position_confidence_ellipse, const std::array< double, 4 > &covariance_matrix, const double object_heading)
 Set the Pos Confidence Ellipse object. More...
 
template<typename T >
void setReferencePosition (T &ref_position, const double latitude, const double longitude, const double altitude=AltitudeValue::UNAVAILABLE)
 Sets the reference position in the given ReferencePostion object. More...
 
template<typename SemiAxisLength >
void setSemiAxis (SemiAxisLength &semi_axis_length, const double length)
 Set the Semi Axis length. More...
 
void setSpeed (Speed &speed, const double value, const double confidence=std::numeric_limits< double >::infinity())
 Set the Speed object. More...
 
void setSpeedConfidence (SpeedConfidence &speed_confidence, const double value)
 Set the Speed Confidence object. More...
 
void setSpeedValue (SpeedValue &speed, const double value)
 Set the SpeedValue object. More...
 
void setTimestampITS (TimestampIts &timestamp_its, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin() ->second)
 Set the TimestampITS object. More...
 
template<typename PosConfidenceEllipse >
void setWGSPosConfidenceEllipse (PosConfidenceEllipse &position_confidence_ellipse, const std::array< double, 4 > &covariance_matrix)
 Set the Pos Confidence Ellipse object. More...
 

Detailed Description

Common setter functions for the ETSI ITS Common Data Dictionary (CDD) v1.3.1 and v2.1.1.

Definition in file cdd_setters_common.h.

Function Documentation

◆ confidenceEllipseFromCovMatrix()

std::tuple<double, double, double> confidenceEllipseFromCovMatrix ( const std::array< double, 4 > &  covariance_matrix,
const double  object_heading 
)
inline

Gets the values needed to set a confidence ellipse from a covariance matrix.

Parameters
covariance_matrixThe four values of the covariance matrix in the order: cov_xx, cov_xy, cov_yx, cov_yy The matrix has to be SPD, otherwise a std::invalid_argument exception is thrown. Its coordinate system is aligned with the object (x = longitudinal, y = lateral)
object_headingThe heading of the object in rad, with respect to WGS84
Returns
std::tuple<double, double, double> semi_major_axis [m], semi_minor_axis [m], orientation [deg], with respect to WGS84

Definition at line 319 of file cdd_setters_common.h.

◆ confidenceEllipseFromWGSCovMatrix()

std::tuple<double, double, double> confidenceEllipseFromWGSCovMatrix ( const std::array< double, 4 > &  covariance_matrix)
inline

Gets the values needed to set a confidence ellipse from a covariance matrix.

Parameters
covariance_matrixThe four values of the covariance matrix in the order: cov_xx, cov_xy, cov_yx, cov_yy The matrix has to be SPD, otherwise a std::invalid_argument exception is thrown. Its coordinate system is aligned with the WGS axes (x = North, y = East)
object_headingThe heading of the object in rad, with respect to WGS84
Returns
std::tuple<double, double, double> semi_major_axis [m], semi_minor_axis [m], orientation [deg], with respect to WGS84

Definition at line 360 of file cdd_setters_common.h.

◆ setAccelerationConfidence()

template<typename AccelerationConfidence >
void setAccelerationConfidence ( AccelerationConfidence &  accel_confidence,
const double  value 
)
inline

Set the Acceleration Confidence object.

Parameters
accel_confidenceobject to set
valuestandard deviation in m/s^2 as decimal number

Definition at line 163 of file cdd_setters_common.h.

◆ setAltitude()

void setAltitude ( Altitude &  altitude,
const double  value 
)
inline

Set the Altitude object.

AltitudeConfidence is set to UNAVAILABLE

Parameters
altitudeobject to set
valueAltitude value (above the reference ellipsoid surface) in meter as decimal number

Definition at line 109 of file cdd_setters_common.h.

◆ setAltitudeValue()

void setAltitudeValue ( AltitudeValue &  altitude,
const double  value 
)
inline

Set the AltitudeValue object.

Parameters
altitudeobject to set
valueAltitudeValue value (above the reference ellipsoid surface) in meter as decimal number

Definition at line 90 of file cdd_setters_common.h.

◆ setFromUTMPosition()

template<typename T >
void setFromUTMPosition ( T &  reference_position,
const gm::PointStamped &  utm_position,
const int  zone,
const bool  northp 
)
inline

Set the ReferencePosition from a given UTM-Position.

The position is transformed to latitude and longitude by using GeographicLib::UTMUPS The z-Coordinate is directly used as altitude value The frame_id of the given utm_position must be set to 'utm_<zone><N/S>'

Parameters
[out]reference_positionReferencePostion or ReferencePositionWithConfidence to set
[in]utm_positiongeometry_msgs::PointStamped describing the given utm position
[in]zonethe UTM zone (zero means UPS) of the given position
[in]northphemisphere (true means north, false means south)

Definition at line 211 of file cdd_setters_common.h.

◆ setHeadingCDD()

template<typename Heading , typename HeadingConfidence = decltype(Heading::heading_confidence)>
void setHeadingCDD ( Heading &  heading,
const double  value,
double  confidence = std::numeric_limits<double>::infinity() 
)

Set the Heading object.

0.0° equals WGS84 North, 90.0° equals WGS84 East, 180.0° equals WGS84 South and 270.0° equals WGS84 West HeadingConfidence is set to UNAVAILABLE

Parameters
headingobject to set
valueHeading value in degree as decimal number
confidencestandard deviation of heading in degree as decimal number (default: infinity, mapping to HeadingConfidence::UNAVAILABLE)

Definition at line 270 of file cdd_setters_common.h.

◆ setHeadingConfidence()

template<typename HeadingConfidence >
void setHeadingConfidence ( HeadingConfidence &  heading_confidence,
const double  value 
)
inline

Set the Heading Confidence object.

Parameters
heading_confidenceobject to set
valuestandard deviation of heading in degree as decimal number

Definition at line 249 of file cdd_setters_common.h.

◆ setHeadingValue()

template<typename HeadingValue >
void setHeadingValue ( HeadingValue &  heading,
const double  value 
)
inline

Set the HeadingValue object.

0.0° equals WGS84 North, 90.0° equals WGS84 East, 180.0° equals WGS84 South and 270.0° equals WGS84 West

Parameters
headingobject to set
valueHeading value in degree as decimal number

Definition at line 236 of file cdd_setters_common.h.

◆ setLatitude()

void setLatitude ( Latitude &  latitude,
const double  deg 
)
inline

Set the Latitude object.

Parameters
latitudeobject to set
degLatitude value in degree as decimal number

Definition at line 66 of file cdd_setters_common.h.

◆ setLongitude()

void setLongitude ( Longitude &  longitude,
const double  deg 
)
inline

Set the Longitude object.

Parameters
longitudeobject to set
degLongitude value in degree as decimal number

Definition at line 78 of file cdd_setters_common.h.

◆ setPosConfidenceEllipse() [1/2]

template<typename PosConfidenceEllipse >
void setPosConfidenceEllipse ( PosConfidenceEllipse &  position_confidence_ellipse,
const double  semi_major_axis,
const double  semi_minor_axis,
const double  orientation 
)
inline

Set the Pos Confidence Ellipse object.

Parameters
[out]position_confidence_ellipseThe PosConfidenceEllipse to set
[in]semi_major_axislength of the semi-major axis in meters
[in]semi_minor_axislength of the semi-minor axis in meters
[in]orientationof the semi-major axis in degrees, with respect to WGS84

Definition at line 303 of file cdd_setters_common.h.

◆ setPosConfidenceEllipse() [2/2]

template<typename PosConfidenceEllipse >
void setPosConfidenceEllipse ( PosConfidenceEllipse &  position_confidence_ellipse,
const std::array< double, 4 > &  covariance_matrix,
const double  object_heading 
)
inline

Set the Pos Confidence Ellipse object.

Parameters
position_confidence_ellipse
covariance_matrixThe four values of the covariance matrix in the order: cov_xx, cov_xy, cov_yx, cov_yy The matrix has to be SPD, otherwise a std::invalid_argument exception is thrown. Its coordinate system is aligned with the object (x = longitudinal, y = lateral)
object_headingThe heading of the object in rad, with respect to WGS84

Definition at line 376 of file cdd_setters_common.h.

◆ setReferencePosition()

template<typename T >
void setReferencePosition ( T &  ref_position,
const double  latitude,
const double  longitude,
const double  altitude = AltitudeValue::UNAVAILABLE 
)
inline

Sets the reference position in the given ReferencePostion object.

This function sets the latitude, longitude, and altitude of the reference position. If the altitude is not provided, it is set to AltitudeValue::UNAVAILABLE.

Parameters
ref_positionReferencePostion or ReferencePositionWithConfidence object to set the reference position in.
latitudeThe latitude value position in degree as decimal number.
longitudeThe longitude value in degree as decimal number.
altitudeThe altitude value (above the reference ellipsoid surface) in meter as decimal number (optional).

Definition at line 185 of file cdd_setters_common.h.

◆ setSemiAxis()

template<typename SemiAxisLength >
void setSemiAxis ( SemiAxisLength &  semi_axis_length,
const double  length 
)
inline

Set the Semi Axis length.

// See https://godbolt.org/z/Eceavfo99 on how the OneCentimeterHelper works with this template

Parameters
semi_axis_lengthThe SemiAxisLength to set
lengththe desired length in meters

Definition at line 284 of file cdd_setters_common.h.

◆ setSpeed()

void setSpeed ( Speed &  speed,
const double  value,
const double  confidence = std::numeric_limits<double>::infinity() 
)
inline

Set the Speed object.

SpeedConfidence is set to UNAVAILABLE

Parameters
speedobject to set
valueSpeed in in m/s as decimal number
confidencestandard deviation in m/s as decimal number (Optional. Default is std::numeric_limits<double>::infinity(), mapping to SpeedConfidence::UNAVAILABLE)

Definition at line 151 of file cdd_setters_common.h.

◆ setSpeedConfidence()

void setSpeedConfidence ( SpeedConfidence &  speed_confidence,
const double  value 
)
inline

Set the Speed Confidence object.

Parameters
speed_confidenceobject to set
valuestandard deviation in m/s as decimal number

Definition at line 132 of file cdd_setters_common.h.

◆ setSpeedValue()

void setSpeedValue ( SpeedValue &  speed,
const double  value 
)
inline

Set the SpeedValue object.

Parameters
speedobject to set
valueSpeedValue in m/s as decimal number

Definition at line 120 of file cdd_setters_common.h.

◆ setTimestampITS()

void setTimestampITS ( TimestampIts &  timestamp_its,
const uint64_t  unix_nanosecs,
const uint16_t  n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second 
)
inline

Set the TimestampITS object.

Parameters
[in]timestamp_itsTimestampITS object to set the timestamp
[in]unix_nanosecsUnix-Nanoseconds to set the timestamp for
[in]n_leap_secondsNumber of leap-seconds since 2004. (Defaults to the todays number of leap seconds since 2004.)
[in]epoch_offsetUnix-Timestamp in seconds for the 01.01.2004 at 00:00:00

Definition at line 52 of file cdd_setters_common.h.

◆ setWGSPosConfidenceEllipse()

template<typename PosConfidenceEllipse >
void setWGSPosConfidenceEllipse ( PosConfidenceEllipse &  position_confidence_ellipse,
const std::array< double, 4 > &  covariance_matrix 
)
inline

Set the Pos Confidence Ellipse object.

Parameters
position_confidence_ellipse
covariance_matrixThe four values of the covariance matrix in the order: cov_xx, cov_xy, cov_yx, cov_yy The matrix has to be SPD, otherwise a std::invalid_argument exception is thrown. Its coordinate system is aligned with the WGS axes (x = North, y = East)
object_headingThe heading of the object in rad, with respect to WGS84

Definition at line 391 of file cdd_setters_common.h.



etsi_its_msgs_utils
Author(s): Jean-Pierre Busch , Guido Küppers , Lennart Reiher
autogenerated on Sun May 18 2025 02:32:12