etsi_its_messages v3.0.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
31
32#pragma once
33
35
36namespace etsi_its_denm_msgs::access {
37
39#include <etsi_its_msgs_utils/impl/asn1_primitives/asn1_primitives_setters.h>
41
44 *
45 * @param denm DENM-Message to set the ItsPduHeader
46 * @param station_id
47 * @param protocol_version
48 */
49inline void setItsPduHeader(DENM& denm, const uint32_t station_id, const uint8_t protocol_version = 0) {
50 setItsPduHeader(denm.header, ItsPduHeader::MESSAGE_ID_DENM, station_id, protocol_version);
51}
52
58 * @param n_leap_seconds Number of leap seconds since 2004 for the given timestamp (Default: etsi_its_msgs::N_LEAP_SECONDS)
59 */
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
71
72 * @param denm DENM-Message to set the station_type value
73 * @param value station_type value to set
74 */
75inline void setStationType(DENM& denm, const int value) { setStationType(denm.denm.management.station_type, value); }
76
83 * @param denm DENM to set the ReferencePosition
84 * @param latitude The latitude value position in degree as decimal number.
85 * @param longitude The longitude value in degree as decimal number.
86 * @param altitude The altitude value (above the reference ellipsoid surface) in meter as decimal number (optional).
87 */
88inline void setReferencePosition(DENM& denm, const double latitude, const double longitude,
89 const double altitude = AltitudeValue::UNAVAILABLE) {
90 setReferencePosition(denm.denm.management.event_position, latitude, longitude, altitude);
91}
92
94
97 *
98 * @param heading object to set
99 * @param value Heading value in degree as decimal number
100 */
101inline void setHeadingValue(HeadingValue& heading, const double value) {
102 int64_t deg = (int64_t)std::round(value * 1e1);
103 throwIfOutOfRange(deg, HeadingValue::MIN, HeadingValue::MAX, "HeadingValue");
104 heading.value = deg;
105}
106
110 * 0.0° equals WGS84 North, 90.0° equals WGS84 East, 180.0° equals WGS84 South and 270.0° equals WGS84 West
111 * HeadingConfidence is set to UNAVAILABLE
112 *
113 * @param heading object to set
114 * @param value Heading value in degree as decimal number
115 */
116inline void setHeading(Heading& heading, const double value) {
117 heading.heading_confidence.value = HeadingConfidence::UNAVAILABLE;
118 setHeadingValue(heading.heading_value, value);
119}
120
121/**
122 * @brief Set the IsHeadingPresent object for DENM
123 *
124 * @param denm DENM to set IsHeadingPresent
125 * @param presence_of_heading IsHeadingPresent-Value (true or false)
126 */
127inline void setIsHeadingPresent(DENM& denm, bool presence_of_heading) {
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}
134
141 * @param denm DENM to set the ReferencePosition
142 * @param value Heading value in degree as decimal number
143 */
144inline void setHeading(DENM& denm, const double heading_val) {
145 if (denm.denm.location_is_present) {
146 setHeading(denm.denm.location.event_position_heading, heading_val);
147 setIsHeadingPresent(denm, true);
148 } else {
149 throw std::invalid_argument("LocationContainer is not present!");
150 }
152
154 * @brief Set the IsSpeedPresent object for DENM
155 *
156 * @param denm DENM to set IsSpeedPresent
157 * @param presence_of_heading IsSpeedPresent-Value (true or false)
158 */
159inline void setIsSpeedPresent(DENM& denm, bool presence_of_speed) {
160 if (denm.denm.location_is_present) {
161 denm.denm.location.event_speed_is_present = presence_of_speed;
162 } else {
163 throw std::invalid_argument("LocationContainer is not present!");
164 }
166
167/**
168 * @brief Set the vehicle speed
169 *
170 * @param denm DENM to set the speed value
171 * @param speed_val speed value to set in m/s as decimal number
172 */
173inline void setSpeed(DENM& denm, const double speed_val) {
174 if (denm.denm.location_is_present) {
175 setSpeed(denm.denm.location.event_speed, speed_val);
176 setIsSpeedPresent(denm, true);
177 } else {
178 throw std::invalid_argument("LocationContainer is not present!");
179 }
180}
181
182/**
183 * @brief Set the ReferencePosition of a DENM from a given UTM-Position
184 *
185 * The position is transformed to latitude and longitude by using GeographicLib::UTMUPS
186 * The z-Coordinate is directly used as altitude value
187 * The frame_id of the given utm_position must be set to 'utm_<zone><N/S>'
188 *
189 * @param[out] denm DENM for which to set the ReferencePosition
190 * @param[in] utm_position geometry_msgs::PointStamped describing the given utm position
191 * @param[in] zone the UTM zone (zero means UPS) of the given position
192 * @param[in] northp hemisphere (true means north, false means south)
193 */
194inline void setFromUTMPosition(DENM& denm, const gm::PointStamped& utm_position, const int& zone, const bool& northp) {
195 setFromUTMPosition(denm.denm.management.event_position, utm_position, zone, northp);
196}
197
200
204inline void setDrivingLaneStatus(DrivingLaneStatus& driving_lane_status, const std::vector<bool>& bits) {
205 setBitString(driving_lane_status, bits);
206}
207
208/**
209 * @brief Set the Lightbar Siren In Use by a vector of bools
211 * @param light_bar_siren_in_use
212 * @param bits
213 */
214inline void setLightBarSirenInUse(LightBarSirenInUse& light_bar_siren_in_use, const std::vector<bool>& bits) {
215 setBitString(light_bar_siren_in_use, bits);
216}
217
218} // namespace etsi_its_denm_msgs::access
void setDrivingLaneStatus(DrivingLaneStatus &driving_lane_status, const std::vector< bool > &bits)
Set the Driving Lane Status by a vector of bools.
Setter functions for the ETSI ITS Common Data Dictionary (CDD) v1.3.1.
Sanity-check functions etc.
File containing constants that are used in the context of ETIS ITS Messages.
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 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.
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 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 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.
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.
void setStationType(StationType &station_type, const uint8_t value)
Set the Station Type.
const std::map< uint64_t, uint16_t > LEAP_SECOND_INSERTIONS_SINCE_2004
std::map that stores all leap second insertions since 2004 with the corresponding unix-date of the in...
Definition denm_access.h:46