mapem_ts_utils.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 #include <ctime>
33 #include <GeographicLib/UTMUPS.hpp>
34 
35 #pragma once
36 
37 namespace etsi_its_mapem_ts_msgs {
38 
39 namespace access {
40 
47  inline uint64_t getUnixSecondsOfYear(const uint64_t unixSecond) {
48 
49  // Get current time as a time_point
50  time_t ts = static_cast<time_t>(unixSecond); // Convert uint64_t to time_t
51 
52  struct tm* timeinfo;
53  timeinfo = gmtime(&ts);
54 
55  // Set the timeinfo to the beginning of the year
56  timeinfo->tm_sec = 0;
57  timeinfo->tm_min = 0;
58  timeinfo->tm_hour = 0;
59  timeinfo->tm_mday = 1;
60  timeinfo->tm_mon = 0;
61 
62  return timegm(timeinfo); // Convert struct tm back to Unix timestamp
63  }
64 
72  inline uint64_t getUnixNanosecondsFromMinuteOfTheYear(const MinuteOfTheYear& moy, const uint64_t unix_nanoseconds_estimate) {
73  return ((uint64_t)(moy.value*60) + getUnixSecondsOfYear(unix_nanoseconds_estimate*1e-9))*1e9;
74  }
75 
83  inline uint64_t getUnixNanosecondsFromMapData(const MapData& map, const uint64_t unix_nanoseconds_estimate) {
84  return getUnixNanosecondsFromMinuteOfTheYear(getMinuteOfTheYear(map), unix_nanoseconds_estimate);
85  }
86 
94  inline uint64_t getUnixNanoseconds(const MAPEM& mapem, const uint64_t unix_timestamp_estimate) {
95  return getUnixNanosecondsFromMapData(mapem.map, unix_timestamp_estimate);
96  }
97 
109  inline gm::PointStamped getUTMPosition(const Position3D& reference_position, int& zone, bool& northp) {
110  gm::PointStamped utm_point;
111  double latitude = getLatitude(reference_position.lat);
112  double longitude = getLongitude(reference_position.lon);
113  if(reference_position.elevation_is_present) utm_point.point.z = getElevation(reference_position.elevation);
114  try {
115  GeographicLib::UTMUPS::Forward(latitude, longitude, zone, northp, utm_point.point.x, utm_point.point.y);
116  std::string hemisphere;
117  if(northp) hemisphere="N";
118  else hemisphere="S";
119  utm_point.header.frame_id="utm_"+std::to_string(zone)+hemisphere;
120  } catch (GeographicLib::GeographicErr& e) {
121  throw std::invalid_argument(e.what());
122  }
123  return utm_point;
124  }
125 
138  inline gm::PointStamped getUTMPositionWithConvergenceAngle(const Position3D& reference_position, int& zone, bool& northp, double& conv_angle) {
139  gm::PointStamped utm_point;
140  double latitude = getLatitude(reference_position.lat);
141  double longitude = getLongitude(reference_position.lon);
142  if(reference_position.elevation_is_present) utm_point.point.z = getElevation(reference_position.elevation);
143  try {
144  double scale;
145  GeographicLib::UTMUPS::Forward(latitude, longitude, zone, northp, utm_point.point.x, utm_point.point.y, conv_angle, scale);
146  std::string hemisphere;
147  if(northp) hemisphere="N";
148  else hemisphere="S";
149  utm_point.header.frame_id="utm_"+std::to_string(zone)+hemisphere;
150  } catch (GeographicLib::GeographicErr& e) {
151  throw std::invalid_argument(e.what());
152  }
153  return utm_point;
154  }
155 
167  inline gm::PointStamped getRefPointUTMPosition(const IntersectionGeometry& intsctn, int& zone, bool& northp) {
168  return getUTMPosition(intsctn.ref_point, zone, northp);
169  }
170 
183  inline gm::PointStamped getRefPointUTMPositionWithConvergenceAngle(const IntersectionGeometry& intsctn, int& zone, bool& northp, double& conv_angle) {
184  return getUTMPositionWithConvergenceAngle(intsctn.ref_point, zone, northp, conv_angle);
185  }
186 
187 } // namespace etsi_its_mapem_ts_msgs
188 } // namespace access
etsi_its_mapem_ts_msgs::access::getUTMPosition
gm::PointStamped getUTMPosition(const Position3D &reference_position, int &zone, bool &northp)
Get the UTM Position defined by the given Position3D.
Definition: mapem_ts_utils.h:109
etsi_its_mapem_ts_msgs
Definition: mapem_ts_getters.h:34
etsi_its_mapem_ts_msgs::access::getUnixNanoseconds
uint64_t getUnixNanoseconds(const MAPEM &mapem, const uint64_t unix_timestamp_estimate)
Get the unix nanoseconds from MinuteOfTheYear object.
Definition: mapem_ts_utils.h:94
etsi_its_mapem_ts_msgs::access::getUnixNanosecondsFromMapData
uint64_t getUnixNanosecondsFromMapData(const MapData &map, const uint64_t unix_nanoseconds_estimate)
Get the unix nanoseconds from MapData object.
Definition: mapem_ts_utils.h:83
etsi_its_mapem_ts_msgs::access::getMinuteOfTheYear
MinuteOfTheYear getMinuteOfTheYear(const MapData &map)
Get the value of MinuteOfTheYear object MapData object.
Definition: mapem_ts_getters.h:47
etsi_its_mapem_ts_msgs::access::getRefPointUTMPositionWithConvergenceAngle
gm::PointStamped getRefPointUTMPositionWithConvergenceAngle(const IntersectionGeometry &intsctn, int &zone, bool &northp, double &conv_angle)
Get the UTM Position of ref_point defined by the Position3D in an IntersectionGeometry object.
Definition: mapem_ts_utils.h:183
etsi_its_mapem_ts_msgs::access::getLongitude
double getLongitude(const Longitude &longitude)
Get the Longitude value.
Definition: mapem_ts_getters.h:119
etsi_its_mapem_ts_msgs::access::getUTMPositionWithConvergenceAngle
gm::PointStamped getUTMPositionWithConvergenceAngle(const Position3D &reference_position, int &zone, bool &northp, double &conv_angle)
Get the UTM Position defined by the given Position3D along with the grid-convergence angle.
Definition: mapem_ts_utils.h:138
etsi_its_mapem_ts_msgs::access::getRefPointUTMPosition
gm::PointStamped getRefPointUTMPosition(const IntersectionGeometry &intsctn, int &zone, bool &northp)
Get the UTM Position of ref_point defined by the Position3D along with the grid-convergence angle in ...
Definition: mapem_ts_utils.h:167
etsi_its_mapem_ts_msgs::access::getUnixNanosecondsFromMinuteOfTheYear
uint64_t getUnixNanosecondsFromMinuteOfTheYear(const MinuteOfTheYear &moy, const uint64_t unix_nanoseconds_estimate)
Get the unix nanoseconds from MinuteOfTheYear object.
Definition: mapem_ts_utils.h:72
etsi_its_mapem_ts_msgs::access::getElevation
double getElevation(const Elevation &elevation)
Get the Elevation value.
Definition: mapem_ts_getters.h:129
etsi_its_mapem_ts_msgs::access::getUnixSecondsOfYear
uint64_t getUnixSecondsOfYear(const uint64_t unixSecond)
Get the unix seconds of the beginning of a year that corresponds to a given unix timestamp.
Definition: mapem_ts_utils.h:47
etsi_its_mapem_ts_msgs::access::getLatitude
double getLatitude(const Latitude &latitude)
Get the Latitude value.
Definition: mapem_ts_getters.h:109


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