Functions
etsi_its_denm_msgs::access Namespace Reference

Functions

double getAltitude (const DENM &denm)
 Get the Altitude value of DENM. More...
 
uint8_t getCauseCode (const DENM &denm)
 Get the Cause Code object. More...
 
std::string getCauseCodeType (const DENM &denm)
 Get the Cause Code Type object. More...
 
std::vector< bool > getDrivingLaneStatus (const DrivingLaneStatus &driving_lane_status)
 Get the Driving Lane Status in form of bool vector. More...
 
double getHeading (const DENM &denm)
 Get the Heading object. More...
 
double getHeadingConfidence (const DENM &denm)
 Get the Heading confidence. More...
 
bool getIsHeadingPresent (const DENM &denm)
 Get the IsHeadingPresent object. More...
 
bool getIsSpeedPresent (const DENM &denm)
 Get the IsSpeedPresent object. More...
 
double getLatitude (const DENM &denm)
 Get the Latitude value of DENM. More...
 
std::vector< bool > getLightBarSirenInUse (const LightBarSirenInUse &light_bar_siren_in_use)
 Get the Lightbar Siren In Use in form of bool vector. More...
 
double getLongitude (const DENM &denm)
 Get the Longitude value of DENM. More...
 
TimestampIts getReferenceTime (const DENM &denm)
 Get the Reference Time object. More...
 
uint64_t getReferenceTimeValue (const DENM &denm)
 Get the ReferenceTime-Value. More...
 
double getSpeed (const DENM &denm)
 Get the vehicle speed. More...
 
double getSpeedConfidence (const DENM &denm)
 Get the Speed Confidence. More...
 
uint32_t getStationID (const DENM &denm)
 Get the Station ID object. More...
 
uint8_t getStationType (const DENM &denm)
 Get the stationType object. More...
 
uint8_t getSubCauseCode (const DENM &denm)
 Get the Sub Cause Code object. More...
 
std::string getSubCauseCodeType (const DENM &denm)
 Get the Sub Cause Code Type object. More...
 
gm::PointStamped getUTMPosition (const DENM &denm)
 
gm::PointStamped getUTMPosition (const DENM &denm, int &zone, bool &northp)
 
void setDrivingLaneStatus (DrivingLaneStatus &driving_lane_status, const std::vector< bool > &bits)
 Set the Driving Lane Status by a vector of bools. More...
 
void setFromUTMPosition (DENM &denm, const gm::PointStamped &utm_position, const int &zone, const bool &northp)
 Set the ReferencePosition of a DENM from a given UTM-Position. More...
 
void setHeading (DENM &denm, const double heading_val, const double confidence=std::numeric_limits< double >::infinity())
 Set the Heading for a DENM. More...
 
void setIsHeadingPresent (DENM &denm, bool presence_of_heading)
 Set the IsHeadingPresent object for DENM. More...
 
void setIsSpeedPresent (DENM &denm, bool presence_of_speed)
 Set the IsSpeedPresent object for DENM. More...
 
void setItsPduHeader (DENM &denm, const uint32_t station_id, const uint8_t protocol_version=0)
 Set the ItsPduHeader-object for a DENM. More...
 
void setLightBarSirenInUse (LightBarSirenInUse &light_bar_siren_in_use, const std::vector< bool > &bits)
 Set the Lightbar Siren In Use by a vector of bools. More...
 
void setReferencePosition (DENM &denm, const double latitude, const double longitude, const double altitude=AltitudeValue::UNAVAILABLE)
 Set the ReferencePositionWithConfidence for a DENM. More...
 
void setReferenceTime (DENM &denm, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin() ->second)
 Set the ReferenceTime-value. More...
 
void setSpeed (DENM &denm, const double speed_val, const double confidence=std::numeric_limits< double >::infinity())
 Set the vehicle speed. More...
 
void setStationType (DENM &denm, const int value)
 Set the StationType for a DENM. More...
 

Function Documentation

◆ getAltitude()

double etsi_its_denm_msgs::access::getAltitude ( const DENM &  denm)
inline

Get the Altitude value of DENM.

Parameters
denmDENM to get the Altitude value from
Returns
Altitude value (above the reference ellipsoid surface) in meter as decimal number

Definition at line 93 of file denm_getters.h.

◆ getCauseCode()

uint8_t etsi_its_denm_msgs::access::getCauseCode ( const DENM &  denm)
inline

Get the Cause Code object.

Parameters
denmDENM to get the causeCode value from
Returns
causeCode value

Definition at line 218 of file denm_getters.h.

◆ getCauseCodeType()

std::string etsi_its_denm_msgs::access::getCauseCodeType ( const DENM &  denm)
inline

Get the Cause Code Type object.

https://www.etsi.org/deliver/etsi_en/302600_302699/30263703/01.02.01_30/en_30263703v010201v.pdf

Parameters
denmDENM to get the causeCodeType value from
Returns
causeCodeType value

Definition at line 236 of file denm_getters.h.

◆ getDrivingLaneStatus()

std::vector<bool> etsi_its_denm_msgs::access::getDrivingLaneStatus ( const DrivingLaneStatus &  driving_lane_status)
inline

Get the Driving Lane Status in form of bool vector.

Parameters
driving_lane_status
Returns
std::vector<bool>

Definition at line 536 of file denm_getters.h.

◆ getHeading()

double etsi_its_denm_msgs::access::getHeading ( const DENM &  denm)
inline

Get the Heading object.

Parameters
denmDENM to get the Heading-Value from
Returns
heading value in degree as decimal number

Definition at line 101 of file denm_getters.h.

◆ getHeadingConfidence()

double etsi_its_denm_msgs::access::getHeadingConfidence ( const DENM &  denm)
inline

Get the Heading confidence.

Parameters
denmDENM to get the Heading-Value from
Returns
standard deviation of heading in degrees as decimal number

Definition at line 119 of file denm_getters.h.

◆ getIsHeadingPresent()

bool etsi_its_denm_msgs::access::getIsHeadingPresent ( const DENM &  denm)
inline

Get the IsHeadingPresent object.

Parameters
denmDENM to get the IsHeadingPresent-Value from
Returns
IsHeadingPresent-Value (true or false)

Definition at line 137 of file denm_getters.h.

◆ getIsSpeedPresent()

bool etsi_its_denm_msgs::access::getIsSpeedPresent ( const DENM &  denm)
inline

Get the IsSpeedPresent object.

Parameters
denmDENM to get the IsSpeedPresent-Value from
Returns
IsSpeedPresent-Value (true or false)

Definition at line 169 of file denm_getters.h.

◆ getLatitude()

double etsi_its_denm_msgs::access::getLatitude ( const DENM &  denm)
inline

Get the Latitude value of DENM.

Parameters
denmDENM to get the Latitude value from
Returns
Latitude value in degree as decimal number

Definition at line 77 of file denm_getters.h.

◆ getLightBarSirenInUse()

std::vector<bool> etsi_its_denm_msgs::access::getLightBarSirenInUse ( const LightBarSirenInUse &  light_bar_siren_in_use)
inline

Get the Lightbar Siren In Use in form of bool vector.

Parameters
light_bar_siren_in_use
Returns
std::vector<bool>

Definition at line 546 of file denm_getters.h.

◆ getLongitude()

double etsi_its_denm_msgs::access::getLongitude ( const DENM &  denm)
inline

Get the Longitude value of DENM.

Parameters
denmDENM to get the Longitude value from
Returns
Longitude value in degree as decimal number

Definition at line 85 of file denm_getters.h.

◆ getReferenceTime()

TimestampIts etsi_its_denm_msgs::access::getReferenceTime ( const DENM &  denm)
inline

Get the Reference Time object.

Parameters
denmDENM to get the ReferenceTime-Value from
Returns
TimestampIts

Definition at line 53 of file denm_getters.h.

◆ getReferenceTimeValue()

uint64_t etsi_its_denm_msgs::access::getReferenceTimeValue ( const DENM &  denm)
inline

Get the ReferenceTime-Value.

Parameters
denmDENM to get the ReferenceTime-Value from
Returns
uint64_t the ReferenceTime-Value

Definition at line 61 of file denm_getters.h.

◆ getSpeed()

double etsi_its_denm_msgs::access::getSpeed ( const DENM &  denm)
inline

Get the vehicle speed.

Parameters
denmDENM to get the speed value from
Returns
speed value in m/s as decimal number

Definition at line 151 of file denm_getters.h.

◆ getSpeedConfidence()

double etsi_its_denm_msgs::access::getSpeedConfidence ( const DENM &  denm)
inline

Get the Speed Confidence.

Parameters
denmDENM to get the Speed Confidence from
Returns
double standard deviation of the speed in m/s as decimal number

Definition at line 183 of file denm_getters.h.

◆ getStationID()

uint32_t etsi_its_denm_msgs::access::getStationID ( const DENM &  denm)
inline

Get the Station ID object.

Parameters
denmDENM to get the StationID value from
Returns
stationID value

Definition at line 45 of file denm_getters.h.

◆ getStationType()

uint8_t etsi_its_denm_msgs::access::getStationType ( const DENM &  denm)
inline

Get the stationType object.

Parameters
denmDENM to get the stationType value from
Returns
stationType value

Definition at line 69 of file denm_getters.h.

◆ getSubCauseCode()

uint8_t etsi_its_denm_msgs::access::getSubCauseCode ( const DENM &  denm)
inline

Get the Sub Cause Code object.

Parameters
denmDENM to get the subCauseCode value from
Returns
subCauseCode value

Definition at line 226 of file denm_getters.h.

◆ getSubCauseCodeType()

std::string etsi_its_denm_msgs::access::getSubCauseCodeType ( const DENM &  denm)
inline

Get the Sub Cause Code Type object.

https://www.etsi.org/deliver/etsi_en/302600_302699/30263703/01.02.01_30/en_30263703v010201v.pdf

Parameters
denmDENM to get the subCauseCodeType value from
Returns
causeCodeType value

Definition at line 308 of file denm_getters.h.

◆ getUTMPosition() [1/2]

gm::PointStamped etsi_its_denm_msgs::access::getUTMPosition ( const DENM &  denm)
inline
Parameters
denmDENM to get the UTM Position from
Returns
gm::PointStamped geometry_msgs::PointStamped of the given position

Definition at line 206 of file denm_getters.h.

◆ getUTMPosition() [2/2]

gm::PointStamped etsi_its_denm_msgs::access::getUTMPosition ( const DENM &  denm,
int &  zone,
bool &  northp 
)
inline
Parameters
denmDENM to get the UTM Position from
zonethe UTM zone (zero means UPS)
northphemisphere (true means north, false means south)
Returns
gm::PointStamped geometry_msgs::PointStamped of the given position

Definition at line 196 of file denm_getters.h.

◆ setDrivingLaneStatus()

void etsi_its_denm_msgs::access::setDrivingLaneStatus ( DrivingLaneStatus &  driving_lane_status,
const std::vector< bool > &  bits 
)
inline

Set the Driving Lane Status by a vector of bools.

Parameters
driving_lane_status
bits

Definition at line 178 of file denm_setters.h.

◆ setFromUTMPosition()

void etsi_its_denm_msgs::access::setFromUTMPosition ( DENM &  denm,
const gm::PointStamped &  utm_position,
const int &  zone,
const bool &  northp 
)
inline

Set the ReferencePosition of a DENM 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]denmDENM for which to set the ReferencePosition
[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 168 of file denm_setters.h.

◆ setHeading()

void etsi_its_denm_msgs::access::setHeading ( DENM &  denm,
const double  heading_val,
const double  confidence = std::numeric_limits<double>::infinity() 
)
inline

Set the Heading for a DENM.

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
denmDENM to set the ReferencePosition
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 117 of file denm_setters.h.

◆ setIsHeadingPresent()

void etsi_its_denm_msgs::access::setIsHeadingPresent ( DENM &  denm,
bool  presence_of_heading 
)
inline

Set the IsHeadingPresent object for DENM.

Parameters
denmDENM to set IsHeadingPresent
presence_of_headingIsHeadingPresent-Value (true or false)

Definition at line 99 of file denm_setters.h.

◆ setIsSpeedPresent()

void etsi_its_denm_msgs::access::setIsSpeedPresent ( DENM &  denm,
bool  presence_of_speed 
)
inline

Set the IsSpeedPresent object for DENM.

Parameters
denmDENM to set IsSpeedPresent
presence_of_headingIsSpeedPresent-Value (true or false)

Definition at line 132 of file denm_setters.h.

◆ setItsPduHeader()

void etsi_its_denm_msgs::access::setItsPduHeader ( DENM &  denm,
const uint32_t  station_id,
const uint8_t  protocol_version = 0 
)
inline

Set the ItsPduHeader-object for a DENM.

Parameters
denmDENM-Message to set the ItsPduHeader
station_id
protocol_version

Definition at line 49 of file denm_setters.h.

◆ setLightBarSirenInUse()

void etsi_its_denm_msgs::access::setLightBarSirenInUse ( LightBarSirenInUse &  light_bar_siren_in_use,
const std::vector< bool > &  bits 
)
inline

Set the Lightbar Siren In Use by a vector of bools.

Parameters
light_bar_siren_in_use
bits

Definition at line 188 of file denm_setters.h.

◆ setReferencePosition()

void etsi_its_denm_msgs::access::setReferencePosition ( DENM &  denm,
const double  latitude,
const double  longitude,
const double  altitude = AltitudeValue::UNAVAILABLE 
)
inline

Set the ReferencePositionWithConfidence for a DENM.

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

Parameters
denmDENM to set the ReferencePosition
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 88 of file denm_setters.h.

◆ setReferenceTime()

void etsi_its_denm_msgs::access::setReferenceTime ( DENM &  denm,
const uint64_t  unix_nanosecs,
const uint16_t  n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second 
)
inline

Set the ReferenceTime-value.

Parameters
denmDENM to set the ReferenceTime-Value for
unix_nanosecsTimestamp in unix-nanoseconds to set the ReferenceTime-Value from
n_leap_secondsNumber of leap seconds since 2004 for the given timestamp (Defaults to the todays number of leap seconds since 2004.)

Definition at line 60 of file denm_setters.h.

◆ setSpeed()

void etsi_its_denm_msgs::access::setSpeed ( DENM &  denm,
const double  speed_val,
const double  confidence = std::numeric_limits<double>::infinity() 
)
inline

Set the vehicle speed.

Parameters
denmDENM to set the speed value
speed_valspeed value to set in m/s as decimal number
confidencespeed confidence value to set in m/s (default: infinity, mapping to SpeedConfidence::UNAVAILABLE)

Definition at line 147 of file denm_setters.h.

◆ setStationType()

void etsi_its_denm_msgs::access::setStationType ( DENM &  denm,
const int  value 
)
inline

Set the StationType for a DENM.

Parameters
denmDENM-Message to set the station_type value
valuestation_type value to set

Definition at line 75 of file denm_setters.h.



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