cdd_getters_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_GETTERS_COMMON_H
33 #define ETSI_ITS_MSGS_UTILS_IMPL_CDD_CDD_GETTERS_COMMON_H
34 
35 #include <array>
36 #include <cmath>
37 #include <cstdint>
38 #include <GeographicLib/UTMUPS.hpp>
39 
46 inline uint32_t getStationID(const ItsPduHeader& header) { return header.station_id.value; }
47 
54 inline double getLatitude(const Latitude& latitude) { return ((double)latitude.value) * 1e-7; }
55 
62 inline double getLongitude(const Longitude& longitude) { return ((double)longitude.value) * 1e-7; }
63 
70 inline double getAltitude(const Altitude& altitude) { return ((double)altitude.altitude_value.value) * 1e-2; }
71 
78 inline double getSpeed(const Speed& speed) { return ((double)speed.speed_value.value) * 1e-2; }
79 
86 inline double getSpeedConfidence(const Speed& speed) {
87  return ((double)speed.speed_confidence.value) / etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR * 1e-2;
88 }
89 
101 template <typename T>
102 inline gm::PointStamped getUTMPosition(const T& reference_position, int& zone, bool& northp) {
103  gm::PointStamped utm_point;
104  double latitude = getLatitude(reference_position.latitude);
105  double longitude = getLongitude(reference_position.longitude);
106  utm_point.point.z = getAltitude(reference_position.altitude);
107  try {
108  GeographicLib::UTMUPS::Forward(latitude, longitude, zone, northp, utm_point.point.x, utm_point.point.y);
109  std::string hemisphere;
110  if (northp) {
111  hemisphere = "N";
112  } else {
113  hemisphere = "S";
114  }
115  utm_point.header.frame_id = "utm_" + std::to_string(zone) + hemisphere;
116  } catch (GeographicLib::GeographicErr& e) {
117  throw std::invalid_argument(e.what());
118  }
119  return utm_point;
120 }
121 
130 template <typename Heading>
131 inline double getHeadingCDD(const Heading& heading) { return ((double)heading.heading_value.value) * 1e-1; }
132 
141 template <typename Heading>
142 inline double getHeadingConfidenceCDD(const Heading& heading) { return ((double)heading.heading_confidence.value) * 1e-1 / etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; }
143 
150 template <typename SemiAxisLength>
151 inline double getSemiAxis(const SemiAxisLength& semi_axis_length) {
152  return ((double)semi_axis_length.value) * 1e-2 / etsi_its_msgs::OneCentimeterHelper<SemiAxisLength>::value;
153 }
154 
161 template <typename PosConfidenceEllipse>
162 inline std::tuple<double, double, double> getPosConfidenceEllipse(const PosConfidenceEllipse& position_confidence_ellipse) {
163  return {
164  getSemiAxis(position_confidence_ellipse.semi_major_confidence),
165  getSemiAxis(position_confidence_ellipse.semi_minor_confidence),
166  position_confidence_ellipse.semi_major_orientation.value * 1e-1
167  };
168 }
169 
181 inline std::array<double, 4> CovMatrixFromConfidenceEllipse(double semi_major, double semi_minor, double major_orientation, const double object_heading) {
182  std::array<double, 4> covariance_matrix;
183  double semi_major_squared = semi_major * semi_major / (etsi_its_msgs::TWO_D_GAUSSIAN_FACTOR * etsi_its_msgs::TWO_D_GAUSSIAN_FACTOR);
184  double semi_minor_squared = semi_minor * semi_minor / (etsi_its_msgs::TWO_D_GAUSSIAN_FACTOR * etsi_its_msgs::TWO_D_GAUSSIAN_FACTOR);
185  double major_orientation_rad = major_orientation * M_PI / 180;
186  double object_heading_rad = object_heading;
187 
188  double angle_to_object = object_heading_rad - major_orientation_rad;
189 
190  double cos_angle = std::cos(angle_to_object);
191  double sin_angle = std::sin(angle_to_object);
192  covariance_matrix[0] = semi_major_squared * cos_angle * cos_angle + semi_minor_squared * sin_angle * sin_angle;
193  covariance_matrix[1] = (semi_major_squared - semi_minor_squared) * cos_angle * sin_angle;
194  covariance_matrix[2] = covariance_matrix[1];
195  covariance_matrix[3] = semi_major_squared * sin_angle * sin_angle + semi_minor_squared * cos_angle * cos_angle;
196 
197  return covariance_matrix;
198 }
199 
210 inline std::array<double, 4> WGSCovMatrixFromConfidenceEllipse(double semi_major, double semi_minor, double major_orientation) {
211  // The WGS covariance matrix is the same as in vehicle coordinates, if it would have a heading of 0.0
212  return CovMatrixFromConfidenceEllipse(semi_major, semi_minor, major_orientation, 0.0);
213 }
214 
222 template <typename PosConfidenceEllipse>
223 inline std::array<double, 4> getPosConfidenceEllipse(const PosConfidenceEllipse& position_confidence_ellipse, const double object_heading){
224  auto [semi_major, semi_minor, major_orientation] = getPosConfidenceEllipse(position_confidence_ellipse);
225  return CovMatrixFromConfidenceEllipse(semi_major, semi_minor, major_orientation, object_heading);
226 }
227 
235 template <typename PosConfidenceEllipse>
236 inline std::array<double, 4> getWGSPosConfidenceEllipse(const PosConfidenceEllipse& position_confidence_ellipse){
237  auto [semi_major, semi_minor, major_orientation] = getPosConfidenceEllipse(position_confidence_ellipse);
238  return WGSCovMatrixFromConfidenceEllipse(semi_major, semi_minor, major_orientation);
239 }
240 
241 #endif // ETSI_ITS_MSGS_UTILS_IMPL_CDD_CDD_GETTERS_COMMON_H
getAltitude
double getAltitude(const Altitude &altitude)
Get the Altitude value.
Definition: cdd_getters_common.h:70
getSemiAxis
double getSemiAxis(const SemiAxisLength &semi_axis_length)
Get the Semi Axis object.
Definition: cdd_getters_common.h:151
getStationID
uint32_t getStationID(const ItsPduHeader &header)
Get the StationID of ItsPduHeader.
Definition: cdd_getters_common.h:46
etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR
constexpr const double ONE_D_GAUSSIAN_FACTOR
Definition: constants.h:71
getWGSPosConfidenceEllipse
std::array< double, 4 > getWGSPosConfidenceEllipse(const PosConfidenceEllipse &position_confidence_ellipse)
Get the covariance matrix of the position confidence ellipse.
Definition: cdd_getters_common.h:236
CovMatrixFromConfidenceEllipse
std::array< double, 4 > CovMatrixFromConfidenceEllipse(double semi_major, double semi_minor, double major_orientation, const double object_heading)
Convert the confidence ellipse to a covariance matrix.
Definition: cdd_getters_common.h:181
getHeadingConfidenceCDD
double getHeadingConfidenceCDD(const Heading &heading)
Get the Heading value.
Definition: cdd_getters_common.h:142
WGSCovMatrixFromConfidenceEllipse
std::array< double, 4 > WGSCovMatrixFromConfidenceEllipse(double semi_major, double semi_minor, double major_orientation)
Convert the confidence ellipse to a covariance matrix.
Definition: cdd_getters_common.h:210
getUTMPosition
gm::PointStamped getUTMPosition(const T &reference_position, int &zone, bool &northp)
Get the UTM Position defined by the given ReferencePosition.
Definition: cdd_getters_common.h:102
getPosConfidenceEllipse
std::tuple< double, double, double > getPosConfidenceEllipse(const PosConfidenceEllipse &position_confidence_ellipse)
Extract major axis length, minor axis length and orientation from the given position confidence ellip...
Definition: cdd_getters_common.h:162
etsi_its_msgs::TWO_D_GAUSSIAN_FACTOR
constexpr const double TWO_D_GAUSSIAN_FACTOR
Definition: constants.h:75
etsi_its_msgs::OneCentimeterHelper
Definition: constants.h:81
getLatitude
double getLatitude(const Latitude &latitude)
Get the Latitude value.
Definition: cdd_getters_common.h:54
getSpeedConfidence
double getSpeedConfidence(const Speed &speed)
Get the Speed Confidence.
Definition: cdd_getters_common.h:86
getSpeed
double getSpeed(const Speed &speed)
Get the vehicle speed.
Definition: cdd_getters_common.h:78
getLongitude
double getLongitude(const Longitude &longitude)
Get the Longitude value.
Definition: cdd_getters_common.h:62
header
const std::string header
getHeadingCDD
double getHeadingCDD(const Heading &heading)
Get the Heading value.
Definition: cdd_getters_common.h:131


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