cdd_setters_common.h
Go to the documentation of this file.
1 /*
2 =============================================================================
3 MIT License
4 
5 Copyright (c) 2023-2025 Institute for Automotive Engineering (ika), RWTH Aachen University
6 
7 Permission is hereby granted, free of charge, to any person obtaining a copy
8 of this software and associated documentation files (the "Software"), to deal
9 in the Software without restriction, including without limitation the rights
10 to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
11 copies of the Software, and to permit persons to whom the Software is
12 furnished to do so, subject to the following conditions:
13 
14 The above copyright notice and this permission notice shall be included in all
15 copies or substantial portions of the Software.
16 
17 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
18 IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
19 FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
20 AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
21 LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
22 OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
23 SOFTWARE.
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 <array>
39 #include <cmath>
40 #include <cstdint>
41 #include <cstring>
42 #include <type_traits>
43 
52 inline void setTimestampITS(
53  TimestampIts& timestamp_its, const uint64_t unix_nanosecs,
54  const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
55  uint64_t t_its = unix_nanosecs * 1e-6 + (uint64_t)(n_leap_seconds * 1e3) - etsi_its_msgs::UNIX_SECONDS_2004 * 1e3;
56  throwIfOutOfRange(t_its, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
57  timestamp_its.value = t_its;
58 }
59 
66 inline void setLatitude(Latitude& latitude, const double deg) {
67  int64_t angle_in_10_micro_degree = (int64_t)std::round(deg * 1e7);
68  throwIfOutOfRange(angle_in_10_micro_degree, Latitude::MIN, Latitude::MAX, "Latitude");
69  latitude.value = angle_in_10_micro_degree;
70 }
71 
78 inline void setLongitude(Longitude& longitude, const double deg) {
79  int64_t angle_in_10_micro_degree = (int64_t)std::round(deg * 1e7);
80  throwIfOutOfRange(angle_in_10_micro_degree, Longitude::MIN, Longitude::MAX, "Longitude");
81  longitude.value = angle_in_10_micro_degree;
82 }
83 
90 inline void setAltitudeValue(AltitudeValue& altitude, const double value) {
91  int64_t alt_in_cm = (int64_t)std::round(value * 1e2);
92  if (alt_in_cm >= AltitudeValue::MIN && alt_in_cm <= AltitudeValue::MAX) {
93  altitude.value = alt_in_cm;
94  } else if (alt_in_cm < AltitudeValue::MIN) {
95  altitude.value = AltitudeValue::MIN;
96  } else if (alt_in_cm > AltitudeValue::MAX) {
97  altitude.value = AltitudeValue::MAX;
98  }
99 }
100 
109 inline void setAltitude(Altitude& altitude, const double value) {
110  altitude.altitude_confidence.value = AltitudeConfidence::UNAVAILABLE;
111  setAltitudeValue(altitude.altitude_value, value);
112 }
113 
120 inline void setSpeedValue(SpeedValue& speed, const double value) {
121  auto speed_val = std::round(value * 1e2);
122  throwIfOutOfRange(speed_val, SpeedValue::MIN, SpeedValue::MAX, "SpeedValue");
123  speed.value = static_cast<decltype(speed.value)>(speed_val);
124 }
125 
132 inline void setSpeedConfidence(SpeedConfidence& speed_confidence, const double value) {
133  auto speed_conf = std::round(value * 1e2 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
134  if (speed_conf < SpeedConfidence::MIN && speed_conf > 0.0){
135  speed_conf = SpeedConfidence::MIN;
136  } else if (speed_conf >= SpeedConfidence::OUT_OF_RANGE || speed_conf <= 0.0) {
137  speed_conf = SpeedConfidence::UNAVAILABLE;
138  }
139  speed_confidence.value = static_cast<decltype(speed_confidence.value)>(speed_conf);
140 }
141 
151 inline void setSpeed(Speed& speed, const double value, const double confidence = std::numeric_limits<double>::infinity()) {
152  setSpeedConfidence(speed.speed_confidence, confidence);
153  setSpeedValue(speed.speed_value, value);
154 }
155 
162 template <typename AccelerationConfidence>
163 inline void setAccelerationConfidence(AccelerationConfidence& accel_confidence, const double value) {
164  auto accel_conf = std::round(value * 1e1 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
165  if (accel_conf < AccelerationConfidence::MIN && accel_conf > 0.0){
166  accel_conf = AccelerationConfidence::MIN;
167  } else if (accel_conf >= AccelerationConfidence::OUT_OF_RANGE || accel_conf <= 0.0) {
168  accel_conf = AccelerationConfidence::UNAVAILABLE;
169  }
170  accel_confidence.value = static_cast<decltype(accel_confidence.value)>(accel_conf);
171 }
172 
184 template <typename T>
185 inline void setReferencePosition(T& ref_position, const double latitude, const double longitude,
186  const double altitude = AltitudeValue::UNAVAILABLE) {
187  setLatitude(ref_position.latitude, latitude);
188  setLongitude(ref_position.longitude, longitude);
189  if (altitude != AltitudeValue::UNAVAILABLE) {
190  setAltitude(ref_position.altitude, altitude);
191  } else {
192  ref_position.altitude.altitude_value.value = AltitudeValue::UNAVAILABLE;
193  ref_position.altitude.altitude_confidence.value = AltitudeConfidence::UNAVAILABLE;
194  }
195  // TODO: set confidence values
196 }
197 
210 template <typename T>
211 inline void setFromUTMPosition(T& reference_position, const gm::PointStamped& utm_position, const int zone,
212  const bool northp) {
213  std::string required_frame_prefix = "utm_";
214  if (utm_position.header.frame_id.rfind(required_frame_prefix, 0) != 0) {
215  throw std::invalid_argument("Frame-ID of UTM Position '" + utm_position.header.frame_id +
216  "' does not start with required prefix '" + required_frame_prefix + "'!");
217  }
218  double latitude, longitude;
219  try {
220  GeographicLib::UTMUPS::Reverse(zone, northp, utm_position.point.x, utm_position.point.y, latitude, longitude);
221  } catch (GeographicLib::GeographicErr& e) {
222  throw std::invalid_argument(e.what());
223  }
224  setReferencePosition(reference_position, latitude, longitude, utm_position.point.z);
225 }
226 
235 template <typename HeadingValue>
236 inline void setHeadingValue(HeadingValue& heading, const double value) {
237  int64_t deg = (int64_t)std::round(value * 1e1);
238  throwIfOutOfRange(deg, HeadingValue::MIN, HeadingValue::MAX, "HeadingValue");
239  heading.value = deg;
240 }
241 
248 template<typename HeadingConfidence>
249 inline void setHeadingConfidence(HeadingConfidence& heading_confidence, const double value) {
250  auto heading_conf = std::round(value * 1e1 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
251  if (heading_conf < HeadingConfidence::MIN && heading_conf > 0.0){
252  heading_conf = HeadingConfidence::MIN;
253  } else if (heading_conf >= HeadingConfidence::OUT_OF_RANGE || heading_conf <= 0.0) {
254  heading_conf = HeadingConfidence::UNAVAILABLE;
255  }
256  heading_confidence.value = static_cast<decltype(heading_confidence.value)>(heading_conf);
257 }
258 
269 template <typename Heading, typename HeadingConfidence = decltype(Heading::heading_confidence)>
270 void setHeadingCDD(Heading& heading, const double value, double confidence = std::numeric_limits<double>::infinity()) {
271  setHeadingConfidence(heading.heading_confidence, confidence);
272  setHeadingValue(heading.heading_value, value);
273 }
274 
283 template <typename SemiAxisLength>
284 inline void setSemiAxis(SemiAxisLength& semi_axis_length, const double length) {
285  double semi_axis_length_val = std::round(length * etsi_its_msgs::OneCentimeterHelper<SemiAxisLength>::value * 1e2);
286  if(semi_axis_length_val < SemiAxisLength::MIN) {
287  semi_axis_length_val = SemiAxisLength::MIN;
288  } else if(semi_axis_length_val >= SemiAxisLength::OUT_OF_RANGE) {
289  semi_axis_length_val = SemiAxisLength::OUT_OF_RANGE;
290  }
291  semi_axis_length.value = static_cast<uint16_t>(semi_axis_length_val);
292 }
293 
302 template <typename PosConfidenceEllipse>
303 inline void setPosConfidenceEllipse(PosConfidenceEllipse& position_confidence_ellipse, const double semi_major_axis,
304  const double semi_minor_axis, const double orientation) {
305  setSemiAxis(position_confidence_ellipse.semi_major_confidence, semi_major_axis);
306  setSemiAxis(position_confidence_ellipse.semi_minor_confidence, semi_minor_axis);
307  setHeadingValue(position_confidence_ellipse.semi_major_orientation, orientation);
308 }
309 
319 inline std::tuple<double, double, double> confidenceEllipseFromCovMatrix(const std::array<double, 4>& covariance_matrix, const double object_heading) {
320 
321  if(std::abs(covariance_matrix[1] - covariance_matrix[2]) > 1e-6) {
322  throw std::invalid_argument("Covariance matrix is not symmetric");
323  }
324  double trace = covariance_matrix[0] + covariance_matrix[3];
325  double determinant = covariance_matrix[0] * covariance_matrix[3] - covariance_matrix[1] * covariance_matrix[1];
326  if (determinant <= 0 || covariance_matrix[0] <= 0) {
327  // https://sites.math.northwestern.edu/~clark/285/2006-07/handouts/pos-def.pdf:
328  // Therefore, a necessary and sufficient condition for the quadratic form of a symmetric 2 × 2 matrix
329  // to be positive definite is for det(A) > 0 and a > 0
330  throw std::invalid_argument("Covariance matrix is not positive definite");
331  }
332  double eigenvalue1 = trace / 2 + std::sqrt(trace * trace / 4 - determinant);
333  double eigenvalue2 = trace / 2 - std::sqrt(trace * trace / 4 - determinant);
334  double semi_major_axis = std::sqrt(eigenvalue1) * etsi_its_msgs::TWO_D_GAUSSIAN_FACTOR;
335  double semi_minor_axis = std::sqrt(eigenvalue2) * etsi_its_msgs::TWO_D_GAUSSIAN_FACTOR;
336  // object_heading - orientation of the ellipse, as WGS84 has positive angles to the right
337  double orientation = object_heading - 0.5 * std::atan2(2 * covariance_matrix[1], covariance_matrix[0] - covariance_matrix[3]);
338  orientation = orientation * 180 / M_PI; // Convert to degrees
339  // Normalize to [0, 180)
340  // 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
341  orientation = std::fmod(orientation + 180, 180);
342  while (orientation < 0) {
343  orientation += 180;
344  }
345  while (orientation >= 180) {
346  orientation -= 180;
347  }
348  return std::make_tuple(semi_major_axis, semi_minor_axis, orientation);
349 }
350 
360 inline std::tuple<double, double, double> confidenceEllipseFromWGSCovMatrix(const std::array<double, 4>& covariance_matrix) {
361  // The resulting ellipse is the same as if the cov matrix was given in vehicle coordinates
362  // and the object heading was set to 0.0
363  return confidenceEllipseFromCovMatrix(covariance_matrix, 0.0);
364 }
365 
375 template <typename PosConfidenceEllipse>
376 inline void setPosConfidenceEllipse(PosConfidenceEllipse& position_confidence_ellipse, const std::array<double, 4>& covariance_matrix, const double object_heading){
377  auto [semi_major_axis, semi_minor_axis, orientation] = confidenceEllipseFromCovMatrix(covariance_matrix, object_heading);
378  setPosConfidenceEllipse(position_confidence_ellipse, semi_major_axis, semi_minor_axis, orientation);
379 }
380 
390 template <typename PosConfidenceEllipse>
391 inline void setWGSPosConfidenceEllipse(PosConfidenceEllipse& position_confidence_ellipse, const std::array<double, 4>& covariance_matrix){
392  auto [semi_major_axis, semi_minor_axis, orientation] = confidenceEllipseFromWGSCovMatrix(covariance_matrix);
393  setPosConfidenceEllipse(position_confidence_ellipse, semi_major_axis, semi_minor_axis, orientation);
394 }
395 
396 
397 
398 #endif // ETSI_ITS_MSGS_UTILS_IMPL_CDD_CDD_SETTERS_COMMON_H
setPosConfidenceEllipse
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.
Definition: cdd_setters_common.h:303
setSemiAxis
void setSemiAxis(SemiAxisLength &semi_axis_length, const double length)
Set the Semi Axis length.
Definition: cdd_setters_common.h:284
checks.h
Sanity-check functions etc.
setSpeedConfidence
void setSpeedConfidence(SpeedConfidence &speed_confidence, const double value)
Set the Speed Confidence object.
Definition: cdd_setters_common.h:132
setAccelerationConfidence
void setAccelerationConfidence(AccelerationConfidence &accel_confidence, const double value)
Set the Acceleration Confidence object.
Definition: cdd_setters_common.h:163
setHeadingCDD
void setHeadingCDD(Heading &heading, const double value, double confidence=std::numeric_limits< double >::infinity())
Set the Heading object.
Definition: cdd_setters_common.h:270
etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR
constexpr const double ONE_D_GAUSSIAN_FACTOR
Definition: constants.h:71
setHeadingConfidence
void setHeadingConfidence(HeadingConfidence &heading_confidence, const double value)
Set the Heading Confidence object.
Definition: cdd_setters_common.h:249
setAltitude
void setAltitude(Altitude &altitude, const double value)
Set the Altitude object.
Definition: cdd_setters_common.h:109
setSpeedValue
void setSpeedValue(SpeedValue &speed, const double value)
Set the SpeedValue object.
Definition: cdd_setters_common.h:120
setWGSPosConfidenceEllipse
void setWGSPosConfidenceEllipse(PosConfidenceEllipse &position_confidence_ellipse, const std::array< double, 4 > &covariance_matrix)
Set the Pos Confidence Ellipse object.
Definition: cdd_setters_common.h:391
setReferencePosition
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.
Definition: cdd_setters_common.h:185
setLatitude
void setLatitude(Latitude &latitude, const double deg)
Set the Latitude object.
Definition: cdd_setters_common.h:66
etsi_its_msgs::TWO_D_GAUSSIAN_FACTOR
constexpr const double TWO_D_GAUSSIAN_FACTOR
Definition: constants.h:75
setLongitude
void setLongitude(Longitude &longitude, const double deg)
Set the Longitude object.
Definition: cdd_setters_common.h:78
etsi_its_msgs::OneCentimeterHelper
Definition: constants.h:81
setFromUTMPosition
void setFromUTMPosition(T &reference_position, const gm::PointStamped &utm_position, const int zone, const bool northp)
Set the ReferencePosition from a given UTM-Position.
Definition: cdd_setters_common.h:211
etsi_its_msgs::UNIX_SECONDS_2004
const uint64_t UNIX_SECONDS_2004
Definition: constants.h:39
confidenceEllipseFromWGSCovMatrix
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.
Definition: cdd_setters_common.h:360
constants.h
File containing constants that are used in the context of ETIS ITS Messages.
setHeadingValue
void setHeadingValue(HeadingValue &heading, const double value)
Set the HeadingValue object.
Definition: cdd_setters_common.h:236
confidenceEllipseFromCovMatrix
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.
Definition: cdd_setters_common.h:319
setTimestampITS
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.
Definition: cdd_setters_common.h:52
length
TF2SIMD_FORCE_INLINE tf2Scalar length(const Quaternion &q)
etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004
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
setAltitudeValue
void setAltitudeValue(AltitudeValue &altitude, const double value)
Set the AltitudeValue object.
Definition: cdd_setters_common.h:90
setSpeed
void setSpeed(Speed &speed, const double value, const double confidence=std::numeric_limits< double >::infinity())
Set the Speed object.
Definition: cdd_setters_common.h:151
throwIfOutOfRange
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


etsi_its_msgs_utils
Author(s): Jean-Pierre Busch , Guido Küppers , Lennart Reiher
autogenerated on Sun May 18 2025 02:32:12