etsi_its_messages 1.0.0
Loading...
Searching...
No Matches
cdd_setters_common.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#ifndef ETSI_ITS_MSGS_UTILS_IMPL_CDD_CDD_SETTERS_COMMON_H
33#define ETSI_ITS_MSGS_UTILS_IMPL_CDD_CDD_SETTERS_COMMON_H
34
37#include <GeographicLib/UTMUPS.hpp>
38#include <cstring>
39
48inline void setTimestampITS(
49 TimestampIts& timestamp_its, const uint64_t unix_nanosecs,
50 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->second) {
51 uint64_t t_its = unix_nanosecs * 1e-6 + (uint64_t)(n_leap_seconds * 1e3) - etsi_its_msgs::UNIX_SECONDS_2004 * 1e3;
52 throwIfOutOfRange(t_its, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
53 timestamp_its.value = t_its;
54}
55
62inline void setLatitude(Latitude& latitude, const double deg) {
63 int64_t angle_in_10_micro_degree = (int64_t)std::round(deg * 1e7);
64 throwIfOutOfRange(angle_in_10_micro_degree, Latitude::MIN, Latitude::MAX, "Latitude");
65 latitude.value = angle_in_10_micro_degree;
66}
67
74inline void setLongitude(Longitude& longitude, const double deg) {
75 int64_t angle_in_10_micro_degree = (int64_t)std::round(deg * 1e7);
76 throwIfOutOfRange(angle_in_10_micro_degree, Longitude::MIN, Longitude::MAX, "Longitude");
77 longitude.value = angle_in_10_micro_degree;
78}
79
86inline void setAltitudeValue(AltitudeValue& altitude, const double value) {
87 int64_t alt_in_cm = (int64_t)std::round(value * 1e2);
88 if (alt_in_cm >= AltitudeValue::MIN && alt_in_cm <= AltitudeValue::MAX) {
89 altitude.value = alt_in_cm;
90 } else if (alt_in_cm < AltitudeValue::MIN) {
91 altitude.value = AltitudeValue::MIN;
92 } else if (alt_in_cm > AltitudeValue::MAX) {
93 altitude.value = AltitudeValue::MAX;
94 }
95}
96
105inline void setAltitude(Altitude& altitude, const double value) {
106 altitude.altitude_confidence.value = AltitudeConfidence::UNAVAILABLE;
107 setAltitudeValue(altitude.altitude_value, value);
108}
109
116inline void setSpeedValue(SpeedValue& speed, const double value) {
117 int64_t speed_val = (int64_t)std::round(value * 1e2);
118 throwIfOutOfRange(speed_val, SpeedValue::MIN, SpeedValue::MAX, "SpeedValue");
119 speed.value = speed_val;
120}
121
130inline void setSpeed(Speed& speed, const double value) {
131 speed.speed_confidence.value = SpeedConfidence::UNAVAILABLE;
132 setSpeedValue(speed.speed_value, value);
133}
134
146template <typename T>
147inline void setReferencePosition(T& ref_position, const double latitude, const double longitude,
148 const double altitude = AltitudeValue::UNAVAILABLE) {
149 setLatitude(ref_position.latitude, latitude);
150 setLongitude(ref_position.longitude, longitude);
151 if (altitude != AltitudeValue::UNAVAILABLE) {
152 setAltitude(ref_position.altitude, altitude);
153 } else {
154 ref_position.altitude.altitude_value.value = AltitudeValue::UNAVAILABLE;
155 ref_position.altitude.altitude_confidence.value = AltitudeConfidence::UNAVAILABLE;
156 }
157 // TODO: set confidence values
158}
159
172template <typename T>
173inline void setFromUTMPosition(T& reference_position, const gm::PointStamped& utm_position, const int zone,
174 const bool northp) {
175 std::string required_frame_prefix = "utm_";
176 if (utm_position.header.frame_id.rfind(required_frame_prefix, 0) != 0) {
177 throw std::invalid_argument("Frame-ID of UTM Position '" + utm_position.header.frame_id +
178 "' does not start with required prefix '" + required_frame_prefix + "'!");
179 }
180 double latitude, longitude;
181 try {
182 GeographicLib::UTMUPS::Reverse(zone, northp, utm_position.point.x, utm_position.point.y, latitude, longitude);
183 } catch (GeographicLib::GeographicErr& e) {
184 throw std::invalid_argument(e.what());
185 }
186 setReferencePosition(reference_position, latitude, longitude, utm_position.point.z);
187}
188
196template <typename T>
197inline void setBitString(T& bitstring, const std::vector<bool>& bits) {
198 // bit string size
199 const int bits_per_byte = 8;
200 const int n_bytes = (bits.size() - 1) / bits_per_byte + 1;
201 const int n_bits = n_bytes * bits_per_byte;
202
203 // init output
204 bitstring.bits_unused = n_bits - bits.size();
205 bitstring.value = std::vector<uint8_t>(n_bytes);
206
207 // loop over all bytes in reverse order
208 for (int byte_idx = n_bytes - 1; byte_idx >= 0; byte_idx--) {
209 // loop over bits in a byte
210 for (int bit_idx_in_byte = 0; bit_idx_in_byte < bits_per_byte; bit_idx_in_byte++) {
211 // map bit index in byte to bit index in total bitstring
212 int bit_idx = (n_bytes - byte_idx - 1) * bits_per_byte + bit_idx_in_byte;
213 if (byte_idx == 0 && bit_idx >= n_bits - bitstring.bits_unused) break;
214
215 // set bit in output bitstring appropriately
216 bitstring.value[byte_idx] |= bits[bit_idx] << bit_idx_in_byte;
217 }
218 }
219}
220
221#endif // ETSI_ITS_MSGS_UTILS_IMPL_CDD_CDD_SETTERS_COMMON_H
Sanity-check functions etc. for the ETSI ITS Common Data Dictionary (CDD)
void setLongitude(Longitude &longitude, const double deg)
Set the Longitude 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 setSpeedValue(SpeedValue &speed, const double value)
Set the SpeedValue object.
void setAltitude(Altitude &altitude, const double value)
Set the Altitude 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 setAltitudeValue(AltitudeValue &altitude, const double value)
Set the AltitudeValue object.
void setBitString(T &bitstring, const std::vector< bool > &bits)
Set a Bit String by a vector of bools.
void setLatitude(Latitude &latitude, const double deg)
Set the Latitude 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 setSpeed(Speed &speed, const double value)
Set the Speed object.
File containing constants that are used in the context of ETIS ITS Messages.