etsi_its_messages v3.0.0
 
Loading...
Searching...
No Matches
denm_setters.h File Reference

Setter functions for the ETSI ITS DENM (EN) More...

#include <etsi_its_msgs_utils/impl/constants.h>
#include <etsi_its_msgs_utils/impl/checks.h>
#include <etsi_its_msgs_utils/impl/asn1_primitives/asn1_primitives_setters.h>
#include <etsi_its_msgs_utils/impl/cdd/cdd_v1-3-1_setters.h>

Go to the source code of this file.

Functions

template<typename T1, typename T2>
void etsi_its_denm_msgs::access::throwIfOutOfRange (const T1 &val, const T2 &min, const T2 &max, const std::string val_desc)
 Throws an exception if a given value is out of a defined range.
 
void etsi_its_denm_msgs::access::throwIfNotPresent (const bool is_present, const std::string val_desc)
 Throws an exception if the given value is not present.
 
template<typename T>
void etsi_its_denm_msgs::access::setBitString (T &bitstring, const std::vector< bool > &bits)
 Set a Bit String by a vector of bools.
 
uint16_t etsi_its_denm_msgs::access::etsi_its_msgs::getLeapSecondInsertionsSince2004 (const uint64_t unix_seconds)
 Get the leap second insertions since 2004 for given unix seconds.
 
void etsi_its_denm_msgs::access::setTimestampITS (TimestampIts &timestamp_its, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end() ->second)
 Set the TimestampITS object.
 
void etsi_its_denm_msgs::access::setLatitude (Latitude &latitude, const double deg)
 Set the Latitude object.
 
void etsi_its_denm_msgs::access::setLongitude (Longitude &longitude, const double deg)
 Set the Longitude object.
 
void etsi_its_denm_msgs::access::setAltitudeValue (AltitudeValue &altitude, const double value)
 Set the AltitudeValue object.
 
void etsi_its_denm_msgs::access::setAltitude (Altitude &altitude, const double value)
 Set the Altitude object.
 
void etsi_its_denm_msgs::access::setSpeedValue (SpeedValue &speed, const double value)
 Set the SpeedValue object.
 
void etsi_its_denm_msgs::access::setSpeed (Speed &speed, const double value)
 Set the Speed object.
 
template<typename T>
void etsi_its_denm_msgs::access::setReferencePosition (T &ref_position, const double latitude, const double longitude, const double altitude=AltitudeValue::UNAVAILABLE)
 Sets the reference position in the given ReferencePostion object.
 
template<typename T>
void etsi_its_denm_msgs::access::setFromUTMPosition (T &reference_position, const gm::PointStamped &utm_position, const int zone, const bool northp)
 Set the ReferencePosition from a given UTM-Position.
 
void etsi_its_denm_msgs::access::setStationId (StationID &station_id, const uint32_t id_value)
 Set the Station Id object.
 
void etsi_its_denm_msgs::access::setItsPduHeader (ItsPduHeader &header, const uint8_t message_id, const uint32_t station_id, const uint8_t protocol_version=0)
 Set the Its Pdu Header object.
 
void etsi_its_denm_msgs::access::setStationType (StationType &station_type, const uint8_t value)
 Set the Station Type.
 
void etsi_its_denm_msgs::access::setItsPduHeader (DENM &denm, const uint32_t station_id, const uint8_t protocol_version=0)
 Set the ItsPduHeader-object for a DENM.
 
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.end() ->second)
 Set the ReferenceTime-value.
 
void etsi_its_denm_msgs::access::setStationType (DENM &denm, const int value)
 Set the StationType for a DENM.
 
void etsi_its_denm_msgs::access::setReferencePosition (DENM &denm, const double latitude, const double longitude, const double altitude=AltitudeValue::UNAVAILABLE)
 Set the ReferencePositionWithConfidence for a DENM.
 
void etsi_its_denm_msgs::access::setHeadingValue (HeadingValue &heading, const double value)
 Set the HeadingValue object.
 
void etsi_its_denm_msgs::access::setHeading (Heading &heading, const double value)
 Set the Heading object.
 
void etsi_its_denm_msgs::access::setIsHeadingPresent (DENM &denm, bool presence_of_heading)
 Set the IsHeadingPresent object for DENM.
 
void etsi_its_denm_msgs::access::setHeading (DENM &denm, const double heading_val)
 Set the Heading for a DENM.
 
void etsi_its_denm_msgs::access::setIsSpeedPresent (DENM &denm, bool presence_of_speed)
 Set the IsSpeedPresent object for DENM.
 
void etsi_its_denm_msgs::access::setSpeed (DENM &denm, const double speed_val)
 Set the vehicle speed.
 
void etsi_its_denm_msgs::access::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.
 
void etsi_its_denm_msgs::access::setDrivingLaneStatus (DrivingLaneStatus &driving_lane_status, const std::vector< bool > &bits)
 Set the Driving Lane Status by a vector of bools.
 
void etsi_its_denm_msgs::access::setLightBarSirenInUse (LightBarSirenInUse &light_bar_siren_in_use, const std::vector< bool > &bits)
 Set the Lightbar Siren In Use by a vector of bools.
 

Detailed Description

Setter functions for the ETSI ITS DENM (EN)

Definition in file denm_setters.h.

Function Documentation

◆ getLeapSecondInsertionsSince2004()

uint16_t etsi_its_denm_msgs::access::etsi_its_msgs::getLeapSecondInsertionsSince2004 ( const uint64_t unix_seconds)
inline

Get the leap second insertions since 2004 for given unix seconds.

Parameters
unix_secondsthe current unix seconds for that the leap second insertions since 2004 shall be provided
Returns
uint16_t the number of leap second insertions since 2004 for unix_seconds

Definition at line 61 of file denm_access.h.

◆ setAltitude()

void etsi_its_denm_msgs::access::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 140 of file denm_setters.h.

◆ setAltitudeValue()

void etsi_its_denm_msgs::access::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 121 of file denm_setters.h.

◆ setBitString()

template<typename T>
void etsi_its_denm_msgs::access::setBitString ( T & bitstring,
const std::vector< bool > & bits )
inline

Set a Bit String by a vector of bools.

Template Parameters
T
Parameters
bitstringBitString to set
bitsvector of bools

Definition at line 44 of file denm_setters.h.

60inline void setReferenceTime(
61 DENM& denm, const uint64_t unix_nanosecs,
62 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->second) {
63 TimestampIts t_its;
64 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
65 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
66 denm.denm.management.reference_time = t_its;
67}
68

◆ 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 270 of file denm_setters.h.

318inline void setItsPduHeader(DENM& denm, const uint32_t station_id, const uint8_t protocol_version = 0) {
319 setItsPduHeader(denm.header, ItsPduHeader::MESSAGE_ID_DENM, station_id, protocol_version);
320}
321
329inline void setReferenceTime(
330 DENM& denm, const uint64_t unix_nanosecs,
331 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->second) {
332 TimestampIts t_its;
333 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
334 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
335 denm.denm.management.reference_time = t_its;
336}
337
344inline void setStationType(DENM& denm, const int value) { setStationType(denm.denm.management.station_type, value); }
345
357inline void setReferencePosition(DENM& denm, const double latitude, const double longitude,
358 const double altitude = AltitudeValue::UNAVAILABLE) {
359 setReferencePosition(denm.denm.management.event_position, latitude, longitude, altitude);
360}
361
370inline void setHeadingValue(HeadingValue& heading, const double value) {
371 int64_t deg = (int64_t)std::round(value * 1e1);
372 throwIfOutOfRange(deg, HeadingValue::MIN, HeadingValue::MAX, "HeadingValue");
373 heading.value = deg;
374}
375
385inline void setHeading(Heading& heading, const double value) {
386 heading.heading_confidence.value = HeadingConfidence::UNAVAILABLE;
387 setHeadingValue(heading.heading_value, value);
388}
389
396inline void setIsHeadingPresent(DENM& denm, bool presence_of_heading) {
397 if (denm.denm.location_is_present) {
398 denm.denm.location.event_position_heading_is_present = presence_of_heading;
399 } else {
400 throw std::invalid_argument("LocationContainer is not present!");
401 }
402}
403
413inline void setHeading(DENM& denm, const double heading_val) {
414 if (denm.denm.location_is_present) {
415 setHeading(denm.denm.location.event_position_heading, heading_val);
416 setIsHeadingPresent(denm, true);
417 } else {
418 throw std::invalid_argument("LocationContainer is not present!");
419 }
420}
421
428inline void setIsSpeedPresent(DENM& denm, bool presence_of_speed) {
429 if (denm.denm.location_is_present) {
430 denm.denm.location.event_speed_is_present = presence_of_speed;
431 } else {
432 throw std::invalid_argument("LocationContainer is not present!");
433 }
434}
435
442inline void setSpeed(DENM& denm, const double speed_val) {
443 if (denm.denm.location_is_present) {
444 setSpeed(denm.denm.location.event_speed, speed_val);
445 setIsSpeedPresent(denm, true);
446 } else {
447 throw std::invalid_argument("LocationContainer is not present!");
448 }
449}
450
463inline void setFromUTMPosition(DENM& denm, const gm::PointStamped& utm_position, const int& zone, const bool& northp) {
464 setFromUTMPosition(denm.denm.management.event_position, utm_position, zone, northp);
465}
466
473inline void setDrivingLaneStatus(DrivingLaneStatus& driving_lane_status, const std::vector<bool>& bits) {
474 setBitString(driving_lane_status, bits);
475}
476
483inline void setLightBarSirenInUse(LightBarSirenInUse& light_bar_siren_in_use, const std::vector<bool>& bits) {
484 setBitString(light_bar_siren_in_use, bits);
485}
486
487} // namespace etsi_its_denm_msgs::access
void setStationType(CAM &cam, const uint8_t value)
Set the StationType for a CAM.
Setter functions for the ETSI ITS Common Data Dictionary (CDD) v1.3.1.
Sanity-check functions etc.
void throwIfOutOfRange(const T1 &val, const T2 &min, const T2 &max, const std::string val_desc)
Throws an exception if a given value is out of a defined range.
void setSpeed(Speed &speed, const double value)
Set the Speed object.
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.
void setDrivingLaneStatus(DrivingLaneStatus &driving_lane_status, const std::vector< bool > &bits)
Set the Driving Lane Status by a vector of bools.
void setHeading(Heading &heading, const double value)
Set the Heading object.
void setIsSpeedPresent(DENM &denm, bool presence_of_speed)
Set the IsSpeedPresent object for DENM.
void setHeadingValue(HeadingValue &heading, const double value)
Set the HeadingValue object.
void setFromUTMPosition(T &reference_position, const gm::PointStamped &utm_position, const int zone, const bool northp)
Set the ReferencePosition from a given UTM-Position.
void setIsHeadingPresent(DENM &denm, bool presence_of_heading)
Set the IsHeadingPresent object for DENM.
void setLightBarSirenInUse(LightBarSirenInUse &light_bar_siren_in_use, const std::vector< bool > &bits)
Set the Lightbar Siren In Use by a vector of bools.
void setBitString(T &bitstring, const std::vector< bool > &bits)
Set a Bit String by a vector of bools.

◆ setFromUTMPosition() [1/2]

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 260 of file denm_setters.h.

295 {
296
298#include <etsi_its_msgs_utils/impl/asn1_primitives/asn1_primitives_setters.h>
300
308inline void setItsPduHeader(DENM& denm, const uint32_t station_id, const uint8_t protocol_version = 0) {
309 setItsPduHeader(denm.header, ItsPduHeader::MESSAGE_ID_DENM, station_id, protocol_version);
310}
311
319inline void setReferenceTime(
320 DENM& denm, const uint64_t unix_nanosecs,
321 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->second) {
322 TimestampIts t_its;
323 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
324 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
325 denm.denm.management.reference_time = t_its;
326}
327
334inline void setStationType(DENM& denm, const int value) { setStationType(denm.denm.management.station_type, value); }
335
347inline void setReferencePosition(DENM& denm, const double latitude, const double longitude,
348 const double altitude = AltitudeValue::UNAVAILABLE) {
349 setReferencePosition(denm.denm.management.event_position, latitude, longitude, altitude);
350}
351
360inline void setHeadingValue(HeadingValue& heading, const double value) {
361 int64_t deg = (int64_t)std::round(value * 1e1);
362 throwIfOutOfRange(deg, HeadingValue::MIN, HeadingValue::MAX, "HeadingValue");
363 heading.value = deg;
364}
365
375inline void setHeading(Heading& heading, const double value) {
376 heading.heading_confidence.value = HeadingConfidence::UNAVAILABLE;
377 setHeadingValue(heading.heading_value, value);
378}
379
386inline void setIsHeadingPresent(DENM& denm, bool presence_of_heading) {
387 if (denm.denm.location_is_present) {
388 denm.denm.location.event_position_heading_is_present = presence_of_heading;
389 } else {
390 throw std::invalid_argument("LocationContainer is not present!");
391 }
392}
393
403inline void setHeading(DENM& denm, const double heading_val) {
404 if (denm.denm.location_is_present) {
405 setHeading(denm.denm.location.event_position_heading, heading_val);
406 setIsHeadingPresent(denm, true);
407 } else {
408 throw std::invalid_argument("LocationContainer is not present!");
409 }
410}
411
418inline void setIsSpeedPresent(DENM& denm, bool presence_of_speed) {
419 if (denm.denm.location_is_present) {
420 denm.denm.location.event_speed_is_present = presence_of_speed;
421 } else {
422 throw std::invalid_argument("LocationContainer is not present!");
423 }
424}
425
432inline void setSpeed(DENM& denm, const double speed_val) {
433 if (denm.denm.location_is_present) {
434 setSpeed(denm.denm.location.event_speed, speed_val);
435 setIsSpeedPresent(denm, true);
436 } else {
437 throw std::invalid_argument("LocationContainer is not present!");
438 }
439}
440
453inline void setFromUTMPosition(DENM& denm, const gm::PointStamped& utm_position, const int& zone, const bool& northp) {
454 setFromUTMPosition(denm.denm.management.event_position, utm_position, zone, northp);
455}
456
463inline void setDrivingLaneStatus(DrivingLaneStatus& driving_lane_status, const std::vector<bool>& bits) {
464 setBitString(driving_lane_status, bits);
465}
466
473inline void setLightBarSirenInUse(LightBarSirenInUse& light_bar_siren_in_use, const std::vector<bool>& bits) {
474 setBitString(light_bar_siren_in_use, bits);
475}
476
477} // namespace etsi_its_denm_msgs::access

◆ setFromUTMPosition() [2/2]

template<typename T>
void etsi_its_denm_msgs::access::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 208 of file denm_setters.h.

214 {
215 setBitString(light_bar_siren_in_use, bits);
216}
217
218} // namespace etsi_its_denm_msgs::access

◆ setHeading() [1/2]

void etsi_its_denm_msgs::access::setHeading ( DENM & denm,
const double heading_val )
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

Definition at line 210 of file denm_setters.h.

214 {
215 setBitString(light_bar_siren_in_use, bits);
216}
217

◆ setHeading() [2/2]

void etsi_its_denm_msgs::access::setHeading ( Heading & heading,
const double value )
inline

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

Definition at line 182 of file denm_setters.h.

◆ setHeadingValue()

void etsi_its_denm_msgs::access::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 167 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 193 of file denm_setters.h.

194 {
195 setFromUTMPosition(denm.denm.management.event_position, utm_position, zone, northp);
196}
197

◆ 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 225 of file denm_setters.h.

273inline void setItsPduHeader(DENM& denm, const uint32_t station_id, const uint8_t protocol_version = 0) {
274 setItsPduHeader(denm.header, ItsPduHeader::MESSAGE_ID_DENM, station_id, protocol_version);
275}
276
284inline void setReferenceTime(
285 DENM& denm, const uint64_t unix_nanosecs,
286 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->second) {
287 TimestampIts t_its;
288 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
289 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
290 denm.denm.management.reference_time = t_its;
291}
292
299inline void setStationType(DENM& denm, const int value) { setStationType(denm.denm.management.station_type, value); }
300
312inline void setReferencePosition(DENM& denm, const double latitude, const double longitude,
313 const double altitude = AltitudeValue::UNAVAILABLE) {
314 setReferencePosition(denm.denm.management.event_position, latitude, longitude, altitude);
315}
316
325inline void setHeadingValue(HeadingValue& heading, const double value) {
326 int64_t deg = (int64_t)std::round(value * 1e1);
327 throwIfOutOfRange(deg, HeadingValue::MIN, HeadingValue::MAX, "HeadingValue");
328 heading.value = deg;
329}
330
340inline void setHeading(Heading& heading, const double value) {
341 heading.heading_confidence.value = HeadingConfidence::UNAVAILABLE;
342 setHeadingValue(heading.heading_value, value);
343}
344
351inline void setIsHeadingPresent(DENM& denm, bool presence_of_heading) {
352 if (denm.denm.location_is_present) {
353 denm.denm.location.event_position_heading_is_present = presence_of_heading;
354 } else {
355 throw std::invalid_argument("LocationContainer is not present!");
356 }
357}
358
368inline void setHeading(DENM& denm, const double heading_val) {
369 if (denm.denm.location_is_present) {
370 setHeading(denm.denm.location.event_position_heading, heading_val);
371 setIsHeadingPresent(denm, true);
372 } else {
373 throw std::invalid_argument("LocationContainer is not present!");
374 }
375}
376
383inline void setIsSpeedPresent(DENM& denm, bool presence_of_speed) {
384 if (denm.denm.location_is_present) {
385 denm.denm.location.event_speed_is_present = presence_of_speed;
386 } else {
387 throw std::invalid_argument("LocationContainer is not present!");
388 }
389}
390
397inline void setSpeed(DENM& denm, const double speed_val) {
398 if (denm.denm.location_is_present) {
399 setSpeed(denm.denm.location.event_speed, speed_val);
400 setIsSpeedPresent(denm, true);
401 } else {
402 throw std::invalid_argument("LocationContainer is not present!");
403 }
404}
405
418inline void setFromUTMPosition(DENM& denm, const gm::PointStamped& utm_position, const int& zone, const bool& northp) {
419 setFromUTMPosition(denm.denm.management.event_position, utm_position, zone, northp);
420}
421
428inline void setDrivingLaneStatus(DrivingLaneStatus& driving_lane_status, const std::vector<bool>& bits) {
429 setBitString(driving_lane_status, bits);
430}
431
438inline void setLightBarSirenInUse(LightBarSirenInUse& light_bar_siren_in_use, const std::vector<bool>& bits) {
439 setBitString(light_bar_siren_in_use, bits);
440}
441
442} // namespace etsi_its_denm_msgs::access

◆ setItsPduHeader() [1/2]

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 115 of file denm_setters.h.

116 {
117 heading.heading_confidence.value = HeadingConfidence::UNAVAILABLE;

◆ setItsPduHeader() [2/2]

void etsi_its_denm_msgs::access::setItsPduHeader ( ItsPduHeader & header,
const uint8_t message_id,
const uint32_t station_id,
const uint8_t protocol_version = 0 )
inline

Set the Its Pdu Header object.

Parameters
headerItsPduHeader to be set
message_idID of the message
station_id
protocol_version

Definition at line 85 of file denm_setters.h.

89 {
90 setReferencePosition(denm.denm.management.event_position, latitude, longitude, altitude);
91}
92

◆ setLatitude()

void etsi_its_denm_msgs::access::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 97 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 280 of file denm_setters.h.

328inline void setItsPduHeader(DENM& denm, const uint32_t station_id, const uint8_t protocol_version = 0) {
329 setItsPduHeader(denm.header, ItsPduHeader::MESSAGE_ID_DENM, station_id, protocol_version);
330}
331
339inline void setReferenceTime(
340 DENM& denm, const uint64_t unix_nanosecs,
341 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->second) {
342 TimestampIts t_its;
343 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
344 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
345 denm.denm.management.reference_time = t_its;
346}
347
354inline void setStationType(DENM& denm, const int value) { setStationType(denm.denm.management.station_type, value); }
355
367inline void setReferencePosition(DENM& denm, const double latitude, const double longitude,
368 const double altitude = AltitudeValue::UNAVAILABLE) {
369 setReferencePosition(denm.denm.management.event_position, latitude, longitude, altitude);
370}
371
380inline void setHeadingValue(HeadingValue& heading, const double value) {
381 int64_t deg = (int64_t)std::round(value * 1e1);
382 throwIfOutOfRange(deg, HeadingValue::MIN, HeadingValue::MAX, "HeadingValue");
383 heading.value = deg;
384}
385
395inline void setHeading(Heading& heading, const double value) {
396 heading.heading_confidence.value = HeadingConfidence::UNAVAILABLE;
397 setHeadingValue(heading.heading_value, value);
398}
399
406inline void setIsHeadingPresent(DENM& denm, bool presence_of_heading) {
407 if (denm.denm.location_is_present) {
408 denm.denm.location.event_position_heading_is_present = presence_of_heading;
409 } else {
410 throw std::invalid_argument("LocationContainer is not present!");
411 }
412}
413
423inline void setHeading(DENM& denm, const double heading_val) {
424 if (denm.denm.location_is_present) {
425 setHeading(denm.denm.location.event_position_heading, heading_val);
426 setIsHeadingPresent(denm, true);
427 } else {
428 throw std::invalid_argument("LocationContainer is not present!");
429 }
430}
431
438inline void setIsSpeedPresent(DENM& denm, bool presence_of_speed) {
439 if (denm.denm.location_is_present) {
440 denm.denm.location.event_speed_is_present = presence_of_speed;
441 } else {
442 throw std::invalid_argument("LocationContainer is not present!");
443 }
444}
445
452inline void setSpeed(DENM& denm, const double speed_val) {
453 if (denm.denm.location_is_present) {
454 setSpeed(denm.denm.location.event_speed, speed_val);
455 setIsSpeedPresent(denm, true);
456 } else {
457 throw std::invalid_argument("LocationContainer is not present!");
458 }
459}
460
473inline void setFromUTMPosition(DENM& denm, const gm::PointStamped& utm_position, const int& zone, const bool& northp) {
474 setFromUTMPosition(denm.denm.management.event_position, utm_position, zone, northp);
475}
476
483inline void setDrivingLaneStatus(DrivingLaneStatus& driving_lane_status, const std::vector<bool>& bits) {
484 setBitString(driving_lane_status, bits);
485}
486
493inline void setLightBarSirenInUse(LightBarSirenInUse& light_bar_siren_in_use, const std::vector<bool>& bits) {
494 setBitString(light_bar_siren_in_use, bits);
495}
496
497} // namespace etsi_its_denm_msgs::access

◆ setLongitude()

void etsi_its_denm_msgs::access::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 109 of file denm_setters.h.

◆ setReferencePosition() [1/2]

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 154 of file denm_setters.h.

◆ setReferencePosition() [2/2]

template<typename T>
void etsi_its_denm_msgs::access::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 182 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.end()->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 (Default: etsi_its_msgs::N_LEAP_SECONDS)

Definition at line 126 of file denm_setters.h.

127 {
128 if (denm.denm.location_is_present) {
129 denm.denm.location.event_position_heading_is_present = presence_of_heading;
130 } else {
131 throw std::invalid_argument("LocationContainer is not present!");
132 }
133}

◆ setSpeed() [1/2]

void etsi_its_denm_msgs::access::setSpeed ( DENM & denm,
const double speed_val )
inline

Set the vehicle speed.

Parameters
denmDENM to set the speed value
speed_valspeed value to set in m/s as decimal number

Definition at line 239 of file denm_setters.h.

274 {
275
277#include <etsi_its_msgs_utils/impl/asn1_primitives/asn1_primitives_setters.h>
279
287inline void setItsPduHeader(DENM& denm, const uint32_t station_id, const uint8_t protocol_version = 0) {
288 setItsPduHeader(denm.header, ItsPduHeader::MESSAGE_ID_DENM, station_id, protocol_version);
289}
290
298inline void setReferenceTime(
299 DENM& denm, const uint64_t unix_nanosecs,
300 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->second) {
301 TimestampIts t_its;
302 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
303 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
304 denm.denm.management.reference_time = t_its;
305}
306
313inline void setStationType(DENM& denm, const int value) { setStationType(denm.denm.management.station_type, value); }
314
326inline void setReferencePosition(DENM& denm, const double latitude, const double longitude,
327 const double altitude = AltitudeValue::UNAVAILABLE) {
328 setReferencePosition(denm.denm.management.event_position, latitude, longitude, altitude);
329}
330
339inline void setHeadingValue(HeadingValue& heading, const double value) {
340 int64_t deg = (int64_t)std::round(value * 1e1);
341 throwIfOutOfRange(deg, HeadingValue::MIN, HeadingValue::MAX, "HeadingValue");
342 heading.value = deg;
343}
344
354inline void setHeading(Heading& heading, const double value) {
355 heading.heading_confidence.value = HeadingConfidence::UNAVAILABLE;
356 setHeadingValue(heading.heading_value, value);
357}
358
365inline void setIsHeadingPresent(DENM& denm, bool presence_of_heading) {
366 if (denm.denm.location_is_present) {
367 denm.denm.location.event_position_heading_is_present = presence_of_heading;
368 } else {
369 throw std::invalid_argument("LocationContainer is not present!");
370 }
371}
372
382inline void setHeading(DENM& denm, const double heading_val) {
383 if (denm.denm.location_is_present) {
384 setHeading(denm.denm.location.event_position_heading, heading_val);
385 setIsHeadingPresent(denm, true);
386 } else {
387 throw std::invalid_argument("LocationContainer is not present!");
388 }
389}
390
397inline void setIsSpeedPresent(DENM& denm, bool presence_of_speed) {
398 if (denm.denm.location_is_present) {
399 denm.denm.location.event_speed_is_present = presence_of_speed;
400 } else {
401 throw std::invalid_argument("LocationContainer is not present!");
402 }
403}
404
411inline void setSpeed(DENM& denm, const double speed_val) {
412 if (denm.denm.location_is_present) {
413 setSpeed(denm.denm.location.event_speed, speed_val);
414 setIsSpeedPresent(denm, true);
415 } else {
416 throw std::invalid_argument("LocationContainer is not present!");
417 }
418}
419
432inline void setFromUTMPosition(DENM& denm, const gm::PointStamped& utm_position, const int& zone, const bool& northp) {
433 setFromUTMPosition(denm.denm.management.event_position, utm_position, zone, northp);
434}
435
442inline void setDrivingLaneStatus(DrivingLaneStatus& driving_lane_status, const std::vector<bool>& bits) {
443 setBitString(driving_lane_status, bits);
444}
445
452inline void setLightBarSirenInUse(LightBarSirenInUse& light_bar_siren_in_use, const std::vector<bool>& bits) {
453 setBitString(light_bar_siren_in_use, bits);
454}
455
456} // namespace etsi_its_denm_msgs::access

◆ setSpeed() [2/2]

void etsi_its_denm_msgs::access::setSpeed ( Speed & speed,
const double value )
inline

Set the Speed object.

SpeedConfidence is set to UNAVAILABLE

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

Definition at line 165 of file denm_setters.h.

◆ setSpeedValue()

void etsi_its_denm_msgs::access::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 151 of file denm_setters.h.

◆ setStationId()

void etsi_its_denm_msgs::access::setStationId ( StationID & station_id,
const uint32_t id_value )
inline

Set the Station Id object.

Parameters
station_id
id_value

Definition at line 72 of file denm_setters.h.

75 { setStationType(denm.denm.management.station_type, value); }
void setStationType(StationType &station_type, const uint8_t value)
Set the Station Type.

◆ setStationType() [1/2]

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 141 of file denm_setters.h.

◆ setStationType() [2/2]

void etsi_its_denm_msgs::access::setStationType ( StationType & station_type,
const uint8_t value )
inline

Set the Station Type.

Parameters
station_type
value

Definition at line 101 of file denm_setters.h.

101 {
102 int64_t deg = (int64_t)std::round(value * 1e1);
103 throwIfOutOfRange(deg, HeadingValue::MIN, HeadingValue::MAX, "HeadingValue");
104 heading.value = deg;

◆ setTimestampITS()

void etsi_its_denm_msgs::access::setTimestampITS ( TimestampIts & timestamp_its,
const uint64_t unix_nanosecs,
const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->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. (Default: etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->second)
[in]epoch_offsetUnix-Timestamp in seconds for the 01.01.2004 at 00:00:00

Definition at line 83 of file denm_setters.h.

89 {

◆ throwIfNotPresent()

void etsi_its_denm_msgs::access::throwIfNotPresent ( const bool is_present,
const std::string val_desc )
inline

Throws an exception if the given value is not present.

Parameters
is_presentWhether the value is present.
val_descDescription of the value for the exception message.

Definition at line 58 of file denm_setters.h.

58 : etsi_its_msgs::N_LEAP_SECONDS)
59 */
60inline void setReferenceTime(
void setReferenceTime(DENM &denm, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end() ->second)
Set the ReferenceTime-value.

◆ throwIfOutOfRange()

template<typename T1, typename T2>
void etsi_its_denm_msgs::access::throwIfOutOfRange ( const T1 & val,
const T2 & min,
const T2 & max,
const std::string val_desc )

Throws an exception if a given value is out of a defined range.

Template Parameters
T1
T2
Parameters
valThe value to check if it is in the range.
minThe minimum value of the range.
maxThe maximum value of the range.
val_descDescription of the value for the exception message.

Definition at line 47 of file denm_setters.h.

49 {
50 setItsPduHeader(denm.header, ItsPduHeader::MESSAGE_ID_DENM, station_id, protocol_version);
51}