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... | |
|
inline |
Get the Altitude value of DENM.
denm | DENM to get the Altitude value from |
Definition at line 93 of file denm_getters.h.
|
inline |
Get the Cause Code object.
denm | DENM to get the causeCode value from |
Definition at line 218 of file denm_getters.h.
|
inline |
Get the Cause Code Type object.
https://www.etsi.org/deliver/etsi_en/302600_302699/30263703/01.02.01_30/en_30263703v010201v.pdf
denm | DENM to get the causeCodeType value from |
Definition at line 236 of file denm_getters.h.
|
inline |
Get the Driving Lane Status in form of bool vector.
driving_lane_status |
Definition at line 536 of file denm_getters.h.
|
inline |
Get the Heading object.
denm | DENM to get the Heading-Value from |
Definition at line 101 of file denm_getters.h.
|
inline |
Get the Heading confidence.
denm | DENM to get the Heading-Value from |
Definition at line 119 of file denm_getters.h.
|
inline |
Get the IsHeadingPresent object.
denm | DENM to get the IsHeadingPresent-Value from |
Definition at line 137 of file denm_getters.h.
|
inline |
Get the IsSpeedPresent object.
denm | DENM to get the IsSpeedPresent-Value from |
Definition at line 169 of file denm_getters.h.
|
inline |
Get the Latitude value of DENM.
denm | DENM to get the Latitude value from |
Definition at line 77 of file denm_getters.h.
|
inline |
Get the Lightbar Siren In Use in form of bool vector.
light_bar_siren_in_use |
Definition at line 546 of file denm_getters.h.
|
inline |
Get the Longitude value of DENM.
denm | DENM to get the Longitude value from |
Definition at line 85 of file denm_getters.h.
|
inline |
Get the Reference Time object.
denm | DENM to get the ReferenceTime-Value from |
Definition at line 53 of file denm_getters.h.
|
inline |
Get the ReferenceTime-Value.
denm | DENM to get the ReferenceTime-Value from |
Definition at line 61 of file denm_getters.h.
|
inline |
Get the vehicle speed.
denm | DENM to get the speed value from |
Definition at line 151 of file denm_getters.h.
|
inline |
Get the Speed Confidence.
denm | DENM to get the Speed Confidence from |
Definition at line 183 of file denm_getters.h.
|
inline |
Get the Station ID object.
denm | DENM to get the StationID value from |
Definition at line 45 of file denm_getters.h.
|
inline |
Get the stationType object.
denm | DENM to get the stationType value from |
Definition at line 69 of file denm_getters.h.
|
inline |
Get the Sub Cause Code object.
denm | DENM to get the subCauseCode value from |
Definition at line 226 of file denm_getters.h.
|
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
denm | DENM to get the subCauseCodeType value from |
Definition at line 308 of file denm_getters.h.
|
inline |
denm | DENM to get the UTM Position from |
Definition at line 206 of file denm_getters.h.
|
inline |
denm | DENM to get the UTM Position from |
zone | the UTM zone (zero means UPS) |
northp | hemisphere (true means north, false means south) |
Definition at line 196 of file denm_getters.h.
|
inline |
Set the Driving Lane Status by a vector of bools.
driving_lane_status | |
bits |
Definition at line 178 of file denm_setters.h.
|
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>'
[out] | denm | DENM for which to set the ReferencePosition |
[in] | utm_position | geometry_msgs::PointStamped describing the given utm position |
[in] | zone | the UTM zone (zero means UPS) of the given position |
[in] | northp | hemisphere (true means north, false means south) |
Definition at line 168 of file denm_setters.h.
|
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
denm | DENM to set the ReferencePosition |
value | Heading value in degree as decimal number |
confidence | standard deviation of heading in degree as decimal number (default: infinity, mapping to HeadingConfidence::UNAVAILABLE) |
Definition at line 117 of file denm_setters.h.
|
inline |
Set the IsHeadingPresent object for DENM.
denm | DENM to set IsHeadingPresent |
presence_of_heading | IsHeadingPresent-Value (true or false) |
Definition at line 99 of file denm_setters.h.
|
inline |
Set the IsSpeedPresent object for DENM.
denm | DENM to set IsSpeedPresent |
presence_of_heading | IsSpeedPresent-Value (true or false) |
Definition at line 132 of file denm_setters.h.
|
inline |
Set the ItsPduHeader-object for a DENM.
denm | DENM-Message to set the ItsPduHeader |
station_id | |
protocol_version |
Definition at line 49 of file denm_setters.h.
|
inline |
Set the Lightbar Siren In Use by a vector of bools.
light_bar_siren_in_use | |
bits |
Definition at line 188 of file denm_setters.h.
|
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.
denm | DENM to set the ReferencePosition |
latitude | The latitude value position in degree as decimal number. |
longitude | The longitude value in degree as decimal number. |
altitude | The altitude value (above the reference ellipsoid surface) in meter as decimal number (optional). |
Definition at line 88 of file denm_setters.h.
|
inline |
Set the ReferenceTime-value.
denm | DENM to set the ReferenceTime-Value for |
unix_nanosecs | Timestamp in unix-nanoseconds to set the ReferenceTime-Value from |
n_leap_seconds | Number 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.
|
inline |
Set the vehicle speed.
denm | DENM to set the speed value |
speed_val | speed value to set in m/s as decimal number |
confidence | speed confidence value to set in m/s (default: infinity, mapping to SpeedConfidence::UNAVAILABLE) |
Definition at line 147 of file denm_setters.h.
|
inline |
Set the StationType for a DENM.
denm | DENM-Message to set the station_type value |
value | station_type value to set |
Definition at line 75 of file denm_setters.h.