mapem_ts_setters.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 #pragma once
33 
34 
35 #include <GeographicLib/UTMUPS.hpp>
36 
37 namespace etsi_its_mapem_ts_msgs {
38 
39 namespace access {
40 
42 
49  inline void setMinuteOfTheYear(MinuteOfTheYear& moy, const uint32_t moy_value) {
50  throwIfOutOfRange(moy_value, MinuteOfTheYear::MIN, MinuteOfTheYear::MAX, "MinuteOfTheYear");
51  moy.value = moy_value;
52  }
53 
60  inline void setMinuteOfTheYear(MapData& map, const uint32_t moy_value) {
61  setMinuteOfTheYear(map.time_stamp, moy_value);
62  }
63 
69  inline void setMinuteOfTheYear(MAPEM& mapem, const uint32_t moy_value) {
70  setMinuteOfTheYear(mapem.map, moy_value);
71  mapem.map.time_stamp_is_present = true;
72  }
73 
80  inline void setIntersectionID(IntersectionID& intsct_id, const uint16_t id_value) {
81  throwIfOutOfRange(id_value, IntersectionID::MIN, IntersectionID::MAX, "IntersectionID");
82  intsct_id.value = id_value;
83  }
84 
91  inline void setIntersectionID(IntersectionGeometry& intsct, const uint16_t id_value) {
92  setIntersectionID(intsct.id.id, id_value);
93  }
94 
101  inline void setLatitude(Latitude& latitude, const double deg) {
102  int64_t angle_in_10_micro_degree = (int64_t)std::round(deg*1e7);
103  throwIfOutOfRange(angle_in_10_micro_degree, Latitude::MIN, Latitude::MAX, "Latitude");
104  latitude.value = angle_in_10_micro_degree;
105  }
106 
113  inline void setLongitude(Longitude& longitude, const double deg) {
114  int64_t angle_in_10_micro_degree = (int64_t)std::round(deg*1e7);
115  throwIfOutOfRange(angle_in_10_micro_degree, Longitude::MIN, Longitude::MAX, "Longitude");
116  longitude.value = angle_in_10_micro_degree;
117  }
118 
125  inline void setElevation(Elevation& elevation, const double value) {
126  int64_t alt_in_dm = (int64_t)std::round(value*1e1);
127  if(alt_in_dm>=Elevation::MIN && alt_in_dm<=Elevation::MAX) elevation.value = alt_in_dm;
128  else if(alt_in_dm<Elevation::MIN) elevation.value = Elevation::MIN;
129  else if(alt_in_dm>Elevation::MAX) elevation.value = Elevation::MAX;
130  }
131 
139  inline void setPosition3D(Position3D& pos, const double latitude, const double longitude) {
140  setLatitude(pos.lat, latitude);
141  setLongitude(pos.lon, longitude);
142  pos.elevation_is_present = false;
143  }
144 
153  inline void setPosition3D(Position3D& pos, const double latitude, const double longitude, const double altitude) {
154  setPosition3D(pos, latitude, longitude);
155  setElevation(pos.elevation, altitude);
156  pos.elevation_is_present = true;
157  }
158 
167  inline void setPosition3D(IntersectionGeometry& intsct, double latitude, double longitude, double altitude) {
168  setPosition3D(intsct.ref_point, latitude, longitude, altitude);
169  }
170 
183  inline void setPosition3DFromUTMPosition(Position3D& reference_position, const gm::PointStamped& utm_position, const int zone, const bool northp) {
184  std::string required_frame_prefix = "utm_";
185  if(utm_position.header.frame_id.rfind(required_frame_prefix, 0) != 0)
186  {
187  throw std::invalid_argument("Frame-ID of UTM Position '"+utm_position.header.frame_id+"' does not start with required prefix '"+required_frame_prefix+"'!");
188  }
189  double latitude, longitude;
190  try {
191  GeographicLib::UTMUPS::Reverse(zone, northp, utm_position.point.x, utm_position.point.y, latitude, longitude);
192  } catch (GeographicLib::GeographicErr& e) {
193  throw std::invalid_argument(e.what());
194  }
195  setPosition3D(reference_position, latitude, longitude, utm_position.point.z);
196  }
197 
198 } // namespace access
199 
200 } // namespace etsi_its_mapem_ts_msgs
etsi_its_mapem_ts_msgs::access::setPosition3DFromUTMPosition
void setPosition3DFromUTMPosition(Position3D &reference_position, const gm::PointStamped &utm_position, const int zone, const bool northp)
Set the Position3D from a given UTM-Position.
Definition: mapem_ts_setters.h:183
etsi_its_mapem_ts_msgs::access::setMinuteOfTheYear
void setMinuteOfTheYear(MinuteOfTheYear &moy, const uint32_t moy_value)
Set the MinuteOfTheYear object.
Definition: mapem_ts_setters.h:49
etsi_its_mapem_ts_msgs
Definition: mapem_ts_getters.h:34
checks.h
Sanity-check functions etc.
etsi_its_mapem_ts_msgs::access::setIntersectionID
void setIntersectionID(IntersectionID &intsct_id, const uint16_t id_value)
Set the IntersectionID value.
Definition: mapem_ts_setters.h:80
etsi_its_mapem_ts_msgs::access::setPosition3D
void setPosition3D(Position3D &pos, const double latitude, const double longitude)
Set the Position3D object.
Definition: mapem_ts_setters.h:139
etsi_its_mapem_ts_msgs::access::setElevation
void setElevation(Elevation &elevation, const double value)
Set the Elevation object.
Definition: mapem_ts_setters.h:125
etsi_its_mapem_ts_msgs::access::setLongitude
void setLongitude(Longitude &longitude, const double deg)
Set the Longitude object.
Definition: mapem_ts_setters.h:113
etsi_its_mapem_ts_msgs::access::setLatitude
void setLatitude(Latitude &latitude, const double deg)
Set the Latitude object.
Definition: mapem_ts_setters.h:101
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