etsi_its_messages 2.4.0
Loading...
Searching...
No Matches
denm_setters.h
Go to the documentation of this file.
1/*
2=============================================================================
3MIT License
4
5Copyright (c) 2023-2024 Institute for Automotive Engineering (ika), RWTH Aachen University
6
7Permission is hereby granted, free of charge, to any person obtaining a copy
8of this software and associated documentation files (the "Software"), to deal
9in the Software without restriction, including without limitation the rights
10to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
11copies of the Software, and to permit persons to whom the Software is
12furnished to do so, subject to the following conditions:
13
14The above copyright notice and this permission notice shall be included in all
15copies or substantial portions of the Software.
16
17THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
18IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
19FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
20AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
21LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
22OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
23SOFTWARE.
24=============================================================================
25*/
26
32#pragma once
33
35
36namespace etsi_its_denm_msgs::access {
37
39
47inline void setItsPduHeader(DENM& denm, const uint32_t station_id, const uint8_t protocol_version = 0) {
48 setItsPduHeader(denm.header, ItsPduHeader::MESSAGE_ID_DENM, station_id, protocol_version);
49}
50
58inline void setReferenceTime(
59 DENM& denm, const uint64_t unix_nanosecs,
60 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->second) {
61 TimestampIts t_its;
62 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
63 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
64 denm.denm.management.reference_time = t_its;
65}
73inline void setStationType(DENM& denm, const int value) { setStationType(denm.denm.management.station_type, value); }
74
86inline void setReferencePosition(DENM& denm, const double latitude, const double longitude,
87 const double altitude = AltitudeValue::UNAVAILABLE) {
88 setReferencePosition(denm.denm.management.event_position, latitude, longitude, altitude);
89}
90
99inline void setHeadingValue(HeadingValue& heading, const double value) {
100 int64_t deg = (int64_t)std::round(value * 1e1);
101 throwIfOutOfRange(deg, HeadingValue::MIN, HeadingValue::MAX, "HeadingValue");
102 heading.value = deg;
103}
104
114inline void setHeading(Heading& heading, const double value) {
115 heading.heading_confidence.value = HeadingConfidence::UNAVAILABLE;
116 setHeadingValue(heading.heading_value, value);
117}
118
125inline void setIsHeadingPresent(DENM& denm, bool presence_of_heading) {
126 if (denm.denm.location_is_present) {
127 denm.denm.location.event_position_heading_is_present = presence_of_heading;
128 } else {
129 throw std::invalid_argument("LocationContainer is not present!");
130 }
131}
132
142inline void setHeading(DENM& denm, const double heading_val) {
143 if (denm.denm.location_is_present) {
144 setHeading(denm.denm.location.event_position_heading, heading_val);
145 setIsHeadingPresent(denm, true);
146 } else {
147 throw std::invalid_argument("LocationContainer is not present!");
149}
150
157inline void setIsSpeedPresent(DENM& denm, bool presence_of_speed) {
158 if (denm.denm.location_is_present) {
159 denm.denm.location.event_speed_is_present = presence_of_speed;
160 } else {
161 throw std::invalid_argument("LocationContainer is not present!");
162 }
164
171inline void setSpeed(DENM& denm, const double speed_val) {
172 if (denm.denm.location_is_present) {
173 setSpeed(denm.denm.location.event_speed, speed_val);
174 setIsSpeedPresent(denm, true);
175 } else {
176 throw std::invalid_argument("LocationContainer is not present!");
177 }
178}
179
192inline void setFromUTMPosition(DENM& denm, const gm::PointStamped& utm_position, const int& zone, const bool& northp) {
193 setFromUTMPosition(denm.denm.management.event_position, utm_position, zone, northp);
194}
195
202inline void setDrivingLaneStatus(DrivingLaneStatus& driving_lane_status, const std::vector<bool>& bits) {
203 setBitString(driving_lane_status, bits);
204}
205
212inline void setLightBarSirenInUse(LightBarSirenInUse& light_bar_siren_in_use, const std::vector<bool>& bits) {
213 setBitString(light_bar_siren_in_use, bits);
214}
215
216} // namespace etsi_its_denm_msgs::access
void setHeading(Heading &heading, const double value)
Set the Heading object.
void 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.
Definition cam_setters.h:83
void setBitString(T &bitstring, const std::vector< bool > &bits)
Set a Bit String by a vector of bools.
void setHeadingValue(HeadingValue &heading, const double value)
Set the HeadingValue object.
void 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.
Definition cam_setters.h:66
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 setDrivingLaneStatus(DrivingLaneStatus &driving_lane_status, const std::vector< bool > &bits)
Set the Driving Lane Status by a vector of bools.
void setFromUTMPosition(T &reference_position, const gm::PointStamped &utm_position, const int zone, const bool northp)
Set the ReferencePosition from a given UTM-Position.
Setter functions for the ETSI ITS Common Data Dictionary (CDD) v1.3.1.
File containing constants that are used in the context of ETIS ITS Messages.
void setReferenceTime(CollectivePerceptionMessage &cpm, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end() ->second)
Sets the reference time in a CPM.
void setIsSpeedPresent(DENM &denm, bool presence_of_speed)
Set the IsSpeedPresent object for DENM.
void setIsHeadingPresent(DENM &denm, bool presence_of_heading)
Set the IsHeadingPresent object for DENM.