etsi_its_messages v3.4.0
Loading...
Searching...
No Matches
cdd_setters_common.h
Go to the documentation of this file.
1/*
2=============================================================================
3MIT License
4
5Copyright (c) 2023-2025 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#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 <array>
39#include <cmath>
40#include <cstdint>
41#include <cstring>
42#include <type_traits>
43
50template <typename StationId>
51inline void setStationId(StationId& station_id, const uint32_t id_value) {
52 throwIfOutOfRange(id_value, StationId::MIN, StationId::MAX, "StationId");
53 station_id.value = id_value;
54}
55
62template <typename StationType>
63inline void setStationType(StationType& station_type, const uint8_t value) {
64 throwIfOutOfRange(value, StationType::MIN, StationType::MAX, "StationType");
65 station_type.value = value;
66}
67
76inline void setTimestampITS(
77 TimestampIts& timestamp_its, const uint64_t unix_nanosecs,
78 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
79 uint64_t t_its = unix_nanosecs * 1e-6 + (uint64_t)(n_leap_seconds * 1e3) - etsi_its_msgs::UNIX_SECONDS_2004 * 1e3;
80 throwIfOutOfRange(t_its, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
81 timestamp_its.value = t_its;
82}
83
90inline void setLatitude(Latitude& latitude, const double deg) {
91 int64_t angle_in_10_micro_degree = (int64_t)std::round(deg * 1e7);
92 throwIfOutOfRange(angle_in_10_micro_degree, Latitude::MIN, Latitude::MAX, "Latitude");
93 latitude.value = angle_in_10_micro_degree;
94}
95
102inline void setLongitude(Longitude& longitude, const double deg) {
103 int64_t angle_in_10_micro_degree = (int64_t)std::round(deg * 1e7);
104 throwIfOutOfRange(angle_in_10_micro_degree, Longitude::MIN, Longitude::MAX, "Longitude");
105 longitude.value = angle_in_10_micro_degree;
106}
107
114inline void setAltitudeValue(AltitudeValue& altitude, const double value) {
115 int64_t alt_in_cm = (int64_t)std::round(value * 1e2);
116 if (alt_in_cm >= AltitudeValue::MIN && alt_in_cm <= AltitudeValue::MAX) {
117 altitude.value = alt_in_cm;
118 } else if (alt_in_cm < AltitudeValue::MIN) {
119 altitude.value = AltitudeValue::MIN;
120 } else if (alt_in_cm > AltitudeValue::MAX) {
121 altitude.value = AltitudeValue::MAX;
122 }
123}
124
133inline void setAltitude(Altitude& altitude, const double value) {
134 altitude.altitude_confidence.value = AltitudeConfidence::UNAVAILABLE;
135 setAltitudeValue(altitude.altitude_value, value);
136}
137
144inline void setSpeedValue(SpeedValue& speed, const double value) {
145 auto speed_val = std::round(value * 1e2);
146 throwIfOutOfRange(speed_val, SpeedValue::MIN, SpeedValue::MAX, "SpeedValue");
147 speed.value = static_cast<decltype(speed.value)>(speed_val);
148}
149
156inline void setSpeedConfidence(SpeedConfidence& speed_confidence, const double value) {
157 auto speed_conf = std::round(value * 1e2 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
158 if (speed_conf < SpeedConfidence::MIN && speed_conf > 0.0){
159 speed_conf = SpeedConfidence::MIN;
160 } else if (speed_conf >= SpeedConfidence::OUT_OF_RANGE || speed_conf <= 0.0) {
161 speed_conf = SpeedConfidence::UNAVAILABLE;
162 }
163 speed_confidence.value = static_cast<decltype(speed_confidence.value)>(speed_conf);
164}
165
175inline void setSpeed(Speed& speed, const double value, const double confidence = std::numeric_limits<double>::infinity()) {
176 setSpeedConfidence(speed.speed_confidence, confidence);
177 setSpeedValue(speed.speed_value, value);
178}
179
186template <typename AccelerationMagnitudeValue>
187inline void setAccelerationMagnitudeValue(AccelerationMagnitudeValue& accel_mag_value, const double value) {
188 auto accel_mag = std::round(value * 1e1);
189 throwIfOutOfRange(accel_mag, AccelerationMagnitudeValue::MIN, AccelerationMagnitudeValue::MAX, "AccelerationMagnitudeValue");
190 accel_mag_value.value = static_cast<decltype(accel_mag_value.value)>(accel_mag);
191}
192
199template <typename AccelerationConfidence>
200inline void setAccelerationMagnitudeConfidence(AccelerationConfidence& accel_mag_confidence, const double value) {
201 auto accel_mag_conf = std::round(value * 1e1 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
202 if (accel_mag_conf < AccelerationConfidence::MIN && accel_mag_conf > 0.0){
203 accel_mag_conf = AccelerationConfidence::MIN;
204 } else if (accel_mag_conf >= AccelerationConfidence::OUT_OF_RANGE || accel_mag_conf <= 0.0) {
205 accel_mag_conf = AccelerationConfidence::UNAVAILABLE;
206 }
207 accel_mag_confidence.value = static_cast<decltype(accel_mag_confidence.value)>(accel_mag_conf);
208}
209
219template<typename AccelerationMagnitude>
220inline void setAccelerationMagnitude(AccelerationMagnitude& accel_mag, const double value,
221 const double confidence = std::numeric_limits<double>::infinity()) {
222 setAccelerationMagnitudeConfidence(accel_mag.acceleration_confidence, confidence);
223 setAccelerationMagnitudeValue(accel_mag.acceleration_magnitude_value, value);
224}
225
232template <typename AccelerationConfidence>
233inline void setAccelerationConfidence(AccelerationConfidence& accel_confidence, const double value) {
234 auto accel_conf = std::round(value * 1e1 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
235 if (accel_conf < AccelerationConfidence::MIN && accel_conf > 0.0){
236 accel_conf = AccelerationConfidence::MIN;
237 } else if (accel_conf >= AccelerationConfidence::OUT_OF_RANGE || accel_conf <= 0.0) {
238 accel_conf = AccelerationConfidence::UNAVAILABLE;
239 }
240 accel_confidence.value = static_cast<decltype(accel_confidence.value)>(accel_conf);
241}
242
254template <typename T>
255inline void setReferencePosition(T& ref_position, const double latitude, const double longitude,
256 const double altitude = AltitudeValue::UNAVAILABLE) {
257 setLatitude(ref_position.latitude, latitude);
258 setLongitude(ref_position.longitude, longitude);
259 if (altitude != AltitudeValue::UNAVAILABLE) {
260 setAltitude(ref_position.altitude, altitude);
261 } else {
262 ref_position.altitude.altitude_value.value = AltitudeValue::UNAVAILABLE;
263 ref_position.altitude.altitude_confidence.value = AltitudeConfidence::UNAVAILABLE;
264 }
265 // TODO: set confidence values
266}
267
280template <typename T>
281inline void setFromUTMPosition(T& reference_position, const gm::PointStamped& utm_position, const int zone,
282 const bool northp) {
283 std::string required_frame_prefix = "utm_";
284 if (utm_position.header.frame_id.rfind(required_frame_prefix, 0) != 0) {
285 throw std::invalid_argument("Frame-ID of UTM Position '" + utm_position.header.frame_id +
286 "' does not start with required prefix '" + required_frame_prefix + "'!");
287 }
288 double latitude, longitude;
289 try {
290 GeographicLib::UTMUPS::Reverse(zone, northp, utm_position.point.x, utm_position.point.y, latitude, longitude);
291 } catch (GeographicLib::GeographicErr& e) {
292 throw std::invalid_argument(e.what());
293 }
294 setReferencePosition(reference_position, latitude, longitude, utm_position.point.z);
295}
296
305template <typename HeadingValue>
306inline void setHeadingValue(HeadingValue& heading, const double value) {
307 int64_t deg = (int64_t)std::round(value * 1e1);
308 throwIfOutOfRange(deg, HeadingValue::MIN, HeadingValue::MAX, "HeadingValue");
309 heading.value = deg;
310}
311
318template<typename HeadingConfidence>
319inline void setHeadingConfidence(HeadingConfidence& heading_confidence, const double value) {
320 auto heading_conf = std::round(value * 1e1 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
321 if (heading_conf < HeadingConfidence::MIN && heading_conf > 0.0){
322 heading_conf = HeadingConfidence::MIN;
323 } else if (heading_conf >= HeadingConfidence::OUT_OF_RANGE || heading_conf <= 0.0) {
324 heading_conf = HeadingConfidence::UNAVAILABLE;
325 }
326 heading_confidence.value = static_cast<decltype(heading_confidence.value)>(heading_conf);
327}
328
339template <typename Heading, typename HeadingConfidence = decltype(Heading::heading_confidence)>
340void setHeadingCDD(Heading& heading, const double value, double confidence = std::numeric_limits<double>::infinity()) {
341 setHeadingConfidence(heading.heading_confidence, confidence);
342 setHeadingValue(heading.heading_value, value);
343}
344
352template <typename YawRate, typename YawRateValue = decltype(YawRate::yaw_rate_value), typename YawRateConfidence = decltype(YawRate::yaw_rate_confidence)>
353inline void setYawRateCDD(YawRate& yaw_rate, const double value,
354 double confidence = std::numeric_limits<double>::infinity()) {
355 double yaw_rate_in_001_degrees = value * 100.0;
356 // limit value range
357 if (yaw_rate_in_001_degrees < YawRateValue::MIN) {
358 yaw_rate_in_001_degrees = YawRateValue::MIN; // MIN should be NEGATIVE_OUT_OF_RANGE, but CAM only has MIN
359 } else if (yaw_rate_in_001_degrees > YawRateValue::MAX - 1) {
360 yaw_rate_in_001_degrees = YawRateValue::MAX - 1; // MAX - 1 should be POSITIVE_OUT_OF_RANGE, but CAM only has MAX
361 }
362
363 yaw_rate.yaw_rate_value.value = static_cast<decltype(yaw_rate.yaw_rate_value.value)>(yaw_rate_in_001_degrees);
364
365 double yaw_rate_std = confidence;
366 if(yaw_rate_std == std::numeric_limits<double>::infinity()) {
367 yaw_rate.yaw_rate_confidence.value = YawRateConfidence::UNAVAILABLE;
368 } else {
369 yaw_rate_std *= etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR;
370 // How stupid is this?!
371 static const std::map<double, uint8_t> confidence_map = {
372 {0.01, YawRateConfidence::DEG_SEC_000_01},
373 {0.05, YawRateConfidence::DEG_SEC_000_05},
374 {0.1, YawRateConfidence::DEG_SEC_000_10},
375 {1.0, YawRateConfidence::DEG_SEC_001_00},
376 {5.0, YawRateConfidence::DEG_SEC_005_00},
377 {10.0, YawRateConfidence::DEG_SEC_010_00},
378 {100.0, YawRateConfidence::DEG_SEC_100_00},
379 {std::numeric_limits<double>::infinity(), YawRateConfidence::OUT_OF_RANGE},
380 };
381 for(const auto& [thresh, conf_val] : confidence_map) {
382 if (yaw_rate_std <= thresh) {
383 yaw_rate.yaw_rate_confidence.value = conf_val;
384 break;
385 }
386 }
387 }
388}
389
398template <typename SemiAxisLength>
399inline void setSemiAxis(SemiAxisLength& semi_axis_length, const double length) {
400 double semi_axis_length_val = std::round(length * etsi_its_msgs::OneCentimeterHelper<SemiAxisLength>::value * 1e2);
401 if(semi_axis_length_val < SemiAxisLength::MIN) {
402 semi_axis_length_val = SemiAxisLength::MIN;
403 } else if(semi_axis_length_val >= SemiAxisLength::OUT_OF_RANGE) {
404 semi_axis_length_val = SemiAxisLength::OUT_OF_RANGE;
405 }
406 semi_axis_length.value = static_cast<uint16_t>(semi_axis_length_val);
407}
408
417template <typename PosConfidenceEllipse>
418inline void setPosConfidenceEllipse(PosConfidenceEllipse& position_confidence_ellipse, const double semi_major_axis,
419 const double semi_minor_axis, const double orientation) {
420 setSemiAxis(position_confidence_ellipse.semi_major_confidence, semi_major_axis);
421 setSemiAxis(position_confidence_ellipse.semi_minor_confidence, semi_minor_axis);
422 setHeadingValue(position_confidence_ellipse.semi_major_orientation, orientation);
423}
424
434inline std::tuple<double, double, double> confidenceEllipseFromCovMatrix(const std::array<double, 4>& covariance_matrix, const double object_heading) {
435
436 if(std::abs(covariance_matrix[1] - covariance_matrix[2]) > 1e-6) {
437 throw std::invalid_argument("Covariance matrix is not symmetric");
438 }
439 double trace = covariance_matrix[0] + covariance_matrix[3];
440 double determinant = covariance_matrix[0] * covariance_matrix[3] - covariance_matrix[1] * covariance_matrix[1];
441 if (determinant <= 0 || covariance_matrix[0] <= 0) {
442 // https://sites.math.northwestern.edu/~clark/285/2006-07/handouts/pos-def.pdf:
443 // Therefore, a necessary and sufficient condition for the quadratic form of a symmetric 2 × 2 matrix
444 // to be positive definite is for det(A) > 0 and a > 0
445 throw std::invalid_argument("Covariance matrix is not positive definite");
446 }
447 double eigenvalue1 = trace / 2 + std::sqrt(trace * trace / 4 - determinant);
448 double eigenvalue2 = trace / 2 - std::sqrt(trace * trace / 4 - determinant);
449 double semi_major_axis = std::sqrt(eigenvalue1) * etsi_its_msgs::TWO_D_GAUSSIAN_FACTOR;
450 double semi_minor_axis = std::sqrt(eigenvalue2) * etsi_its_msgs::TWO_D_GAUSSIAN_FACTOR;
451 // object_heading - orientation of the ellipse, as WGS84 has positive angles to the right
452 double orientation = object_heading - 0.5 * std::atan2(2 * covariance_matrix[1], covariance_matrix[0] - covariance_matrix[3]);
453 orientation = orientation * 180 / M_PI; // Convert to degrees
454 // Normalize to [0, 180)
455 // Not to 0, 360, as the ellipse is symmetric and the orientation is defined as the angle between the semi-major axis and the x-axis
456 orientation = std::fmod(orientation + 180, 180);
457 while (orientation < 0) {
458 orientation += 180;
459 }
460 while (orientation >= 180) {
461 orientation -= 180;
462 }
463 return std::make_tuple(semi_major_axis, semi_minor_axis, orientation);
464}
465
475inline std::tuple<double, double, double> confidenceEllipseFromWGSCovMatrix(const std::array<double, 4>& covariance_matrix) {
476 // The resulting ellipse is the same as if the cov matrix was given in vehicle coordinates
477 // and the object heading was set to 0.0
478 return confidenceEllipseFromCovMatrix(covariance_matrix, 0.0);
479}
480
490template <typename PosConfidenceEllipse>
491inline void setPosConfidenceEllipse(PosConfidenceEllipse& position_confidence_ellipse, const std::array<double, 4>& covariance_matrix, const double object_heading){
492 auto [semi_major_axis, semi_minor_axis, orientation] = confidenceEllipseFromCovMatrix(covariance_matrix, object_heading);
493 setPosConfidenceEllipse(position_confidence_ellipse, semi_major_axis, semi_minor_axis, orientation);
494}
495
505template <typename PosConfidenceEllipse>
506inline void setWGSPosConfidenceEllipse(PosConfidenceEllipse& position_confidence_ellipse, const std::array<double, 4>& covariance_matrix){
507 auto [semi_major_axis, semi_minor_axis, orientation] = confidenceEllipseFromWGSCovMatrix(covariance_matrix);
508 setPosConfidenceEllipse(position_confidence_ellipse, semi_major_axis, semi_minor_axis, orientation);
509}
510
511#endif // ETSI_ITS_MSGS_UTILS_IMPL_CDD_CDD_SETTERS_COMMON_H
void setLongitude(Longitude &longitude, const double deg)
Set the Longitude object.
void setAccelerationConfidence(AccelerationConfidence &accel_confidence, const double value)
Set the Acceleration Confidence object.
void setPosConfidenceEllipse(PosConfidenceEllipse &position_confidence_ellipse, const double semi_major_axis, const double semi_minor_axis, const double orientation)
Set the Pos Confidence Ellipse object.
void setSpeedValue(SpeedValue &speed, const double value)
Set the SpeedValue 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.rbegin() ->second)
Set the TimestampITS object.
void setSpeedConfidence(SpeedConfidence &speed_confidence, const double value)
Set the Speed Confidence object.
void setStationId(StationId &station_id, const uint32_t id_value)
Set the Station Id object.
std::tuple< double, double, double > confidenceEllipseFromCovMatrix(const std::array< double, 4 > &covariance_matrix, const double object_heading)
Gets the values needed to set a confidence ellipse from a covariance matrix.
void setAccelerationMagnitudeValue(AccelerationMagnitudeValue &accel_mag_value, const double value)
Set the Acceleration Magnitude Value object.
void setSemiAxis(SemiAxisLength &semi_axis_length, const double length)
Set the Semi Axis length.
void setStationType(StationType &station_type, const uint8_t value)
Set the Station Type.
void setAltitude(Altitude &altitude, const double value)
Set the Altitude object.
void setYawRateCDD(YawRate &yaw_rate, const double value, double confidence=std::numeric_limits< double >::infinity())
Set the Yaw Rate 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 setHeadingConfidence(HeadingConfidence &heading_confidence, const double value)
Set the Heading Confidence object.
void setSpeed(Speed &speed, const double value, const double confidence=std::numeric_limits< double >::infinity())
Set the Speed object.
void setAccelerationMagnitudeConfidence(AccelerationConfidence &accel_mag_confidence, const double value)
Set the AccelerationMagnitude Confidence object.
void setWGSPosConfidenceEllipse(PosConfidenceEllipse &position_confidence_ellipse, const std::array< double, 4 > &covariance_matrix)
Set the Pos Confidence Ellipse object.
void setAccelerationMagnitude(AccelerationMagnitude &accel_mag, const double value, const double confidence=std::numeric_limits< double >::infinity())
Set the AccelerationMagnitude object.
void setAltitudeValue(AltitudeValue &altitude, const double value)
Set the AltitudeValue object.
void setHeadingCDD(Heading &heading, const double value, double confidence=std::numeric_limits< double >::infinity())
Set the Heading object.
void setHeadingValue(HeadingValue &heading, const double value)
Set the HeadingValue object.
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.
std::tuple< double, double, double > confidenceEllipseFromWGSCovMatrix(const std::array< double, 4 > &covariance_matrix)
Gets the values needed to set a confidence ellipse from a covariance matrix.
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.
Definition checks.h:46
File containing constants that are used in the context of ETIS ITS Messages.
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 constants.h:45