cam_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_CAM_CAM_GETTERS_COMMON_H
33 #define ETSI_ITS_MSGS_UTILS_IMPL_CAM_CAM_GETTERS_COMMON_H
34 
36 
43 inline uint32_t getStationID(const CAM& cam) { return getStationID(cam.header); }
44 
51 inline GenerationDeltaTime getGenerationDeltaTime(const CAM& cam) { return cam.cam.generation_delta_time; }
52 
59 inline uint16_t getGenerationDeltaTimeValue(const CAM& cam) { return getGenerationDeltaTime(cam).value; }
60 
67 inline uint8_t getStationType(const CAM& cam) { return cam.cam.cam_parameters.basic_container.station_type.value; }
68 
75 inline double getLatitude(const CAM& cam) {
76  return getLatitude(cam.cam.cam_parameters.basic_container.reference_position.latitude);
77 }
78 
85 inline double getLongitude(const CAM& cam) {
86  return getLongitude(cam.cam.cam_parameters.basic_container.reference_position.longitude);
87 }
88 
95 inline double getAltitude(const CAM& cam) {
96  return getAltitude(cam.cam.cam_parameters.basic_container.reference_position.altitude);
97 }
98 
107 inline double getHeading(const CAM& cam) {
108  return getHeadingCDD(cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.heading);
109 }
110 
118 inline double getHeadingConfidence(const CAM& cam) {
119  return getHeadingConfidenceCDD(cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.heading);
120 }
121 
128 inline double getVehicleLength(const VehicleLength& vehicle_length) {
129  return ((double)vehicle_length.vehicle_length_value.value) * 1e-1;
130 }
131 
138 inline double getVehicleLength(const CAM& cam) {
139  return getVehicleLength(
140  cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.vehicle_length);
141 }
142 
149 inline double getVehicleWidth(const VehicleWidth& vehicle_width) { return ((double)vehicle_width.value) * 1e-1; }
150 
157 inline double getVehicleWidth(const CAM& cam) {
158  return getVehicleWidth(
159  cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.vehicle_width);
160 }
161 
168 inline double getSpeed(const CAM& cam) {
169  return getSpeed(cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.speed);
170 }
171 
178 inline double getSpeedConfidence(const CAM& cam) {
179  return getSpeedConfidence(
180  cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.speed);
181 }
182 
189 inline double getLongitudinalAcceleration(const CAM& cam) {
191  cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.longitudinal_acceleration);
192 }
193 
200 inline double getLongitudinalAccelerationConfidence(const CAM& cam) {
202  cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.longitudinal_acceleration);
203 }
204 
211 inline double getLateralAcceleration(const CAM& cam) {
212  if (cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency
213  .lateral_acceleration_is_present) {
214  return getLateralAcceleration(
215  cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.lateral_acceleration);
216  } else {
217  throw std::invalid_argument("LateralAcceleration is not present!");
218  }
219 }
220 
227 inline double getLateralAccelerationConfidence(const CAM& cam) {
228  if (cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency
229  .lateral_acceleration_is_present) {
231  cam.cam.cam_parameters.high_frequency_container.basic_vehicle_container_high_frequency.lateral_acceleration);
232  } else {
233  throw std::invalid_argument("LateralAccelerationConfidence is not present!");
234  }
235 }
236 
248 inline gm::PointStamped getUTMPosition(const CAM& cam, int& zone, bool& northp) {
249  return getUTMPosition(cam.cam.cam_parameters.basic_container.reference_position, zone, northp);
250 }
251 
261 inline gm::PointStamped getUTMPosition(const CAM& cam) {
262  int zone;
263  bool northp;
264  return getUTMPosition(cam.cam.cam_parameters.basic_container.reference_position, zone, northp);
265 }
266 
273 inline std::vector<bool> getExteriorLights(const ExteriorLights& exterior_lights) {
274  return getBitString(exterior_lights.value, exterior_lights.bits_unused);
275 }
276 
283 inline std::vector<bool> getExteriorLights(const CAM& cam) {
284  if (cam.cam.cam_parameters.low_frequency_container_is_present) {
285  if (cam.cam.cam_parameters.low_frequency_container.choice ==
286  LowFrequencyContainer::CHOICE_BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY) {
287  return getExteriorLights(
288  cam.cam.cam_parameters.low_frequency_container.basic_vehicle_container_low_frequency.exterior_lights);
289  } else {
290  throw std::invalid_argument("LowFrequencyContainer is not BASIC_VEHICLE_CONTAINER_LOW_FREQUENCY!");
291  }
292  } else {
293  throw std::invalid_argument("LowFrequencyContainer is not present!");
294  }
295 }
296 
303 inline std::vector<bool> getAccelerationControl(const AccelerationControl& acceleration_control) {
304  return getBitString(acceleration_control.value, acceleration_control.bits_unused);
305 }
306 
313 inline std::vector<bool> getDrivingLaneStatus(const DrivingLaneStatus& driving_lane_status) {
314  return getBitString(driving_lane_status.value, driving_lane_status.bits_unused);
315 }
316 
323 inline std::vector<bool> getSpecialTransportType(const SpecialTransportType& special_transport_type) {
324  return getBitString(special_transport_type.value, special_transport_type.bits_unused);
325 }
326 
333 inline std::vector<bool> getLightBarSirenInUse(const LightBarSirenInUse& light_bar_siren_in_use) {
334  return getBitString(light_bar_siren_in_use.value, light_bar_siren_in_use.bits_unused);
335 }
336 
343 inline std::vector<bool> getEmergencyPriority(const EmergencyPriority& emergency_priority) {
344  return getBitString(emergency_priority.value, emergency_priority.bits_unused);
345 }
346 
347 #endif // ETSI_ITS_MSGS_UTILS_IMPL_CAM_CAM_GETTERS_COMMON_H
getGenerationDeltaTimeValue
uint16_t getGenerationDeltaTimeValue(const CAM &cam)
Get the GenerationDeltaTime-Value.
Definition: cam_getters_common.h:59
getLongitudinalAccelerationConfidence
double getLongitudinalAccelerationConfidence(const CAM &cam)
Get the Longitudinal Acceleration Confidence.
Definition: cam_getters_common.h:200
getLatitude
double getLatitude(const CAM &cam)
Get the Latitude value of CAM.
Definition: cam_getters_common.h:75
getVehicleLength
double getVehicleLength(const VehicleLength &vehicle_length)
Get the Vehicle Length.
Definition: cam_getters_common.h:128
getStationType
uint8_t getStationType(const CAM &cam)
Get the stationType object.
Definition: cam_getters_common.h:67
getLongitude
double getLongitude(const CAM &cam)
Get the Longitude value of CAM.
Definition: cam_getters_common.h:85
getBitString
std::vector< bool > getBitString(const std::vector< uint8_t > &buffer, const int bits_unused)
Get a Bit String in form of bool vector.
Definition: asn1_primitives_getters.h:42
getStationID
uint32_t getStationID(const CAM &cam)
Get the Station ID object.
Definition: cam_getters_common.h:43
getLateralAccelerationConfidence
double getLateralAccelerationConfidence(const CAM &cam)
Get the Lateral Acceleration Confidence.
Definition: cam_getters_common.h:227
getEmergencyPriority
std::vector< bool > getEmergencyPriority(const EmergencyPriority &emergency_priority)
Get the Vehicle Role in form of bool vector.
Definition: cam_getters_common.h:343
getExteriorLights
std::vector< bool > getExteriorLights(const ExteriorLights &exterior_lights)
Get the Exterior Lights in form of bool vector.
Definition: cam_getters_common.h:273
getLateralAcceleration
double getLateralAcceleration(const CAM &cam)
Get the lateral acceleration.
Definition: cam_getters_common.h:211
getLightBarSirenInUse
std::vector< bool > getLightBarSirenInUse(const LightBarSirenInUse &light_bar_siren_in_use)
Get the Lightbar Siren In Use in form of bool vector.
Definition: cam_getters_common.h:333
getAltitude
double getAltitude(const CAM &cam)
Get the Altitude value of CAM.
Definition: cam_getters_common.h:95
getHeadingConfidenceCDD
double getHeadingConfidenceCDD(const Heading &heading)
Get the Heading value.
Definition: cdd_getters_common.h:142
getLongitudinalAcceleration
double getLongitudinalAcceleration(const CAM &cam)
Get the longitudinal acceleration.
Definition: cam_getters_common.h:189
getUTMPosition
gm::PointStamped getUTMPosition(const CAM &cam, int &zone, bool &northp)
Get the UTM Position defined within the BasicContainer of the CAM.
Definition: cam_getters_common.h:248
getHeading
double getHeading(const CAM &cam)
Get the Heading value of CAM.
Definition: cam_getters_common.h:107
getVehicleWidth
double getVehicleWidth(const VehicleWidth &vehicle_width)
Get the Vehicle Width.
Definition: cam_getters_common.h:149
getAccelerationControl
std::vector< bool > getAccelerationControl(const AccelerationControl &acceleration_control)
Get Acceleration Control in form of bool vector.
Definition: cam_getters_common.h:303
getDrivingLaneStatus
std::vector< bool > getDrivingLaneStatus(const DrivingLaneStatus &driving_lane_status)
Get the Driving Lane Status in form of bool vector.
Definition: cam_getters_common.h:313
getHeadingConfidence
double getHeadingConfidence(const CAM &cam)
Get the Heading confidence of CAM.
Definition: cam_getters_common.h:118
asn1_primitives_getters.h
getHeadingCDD
double getHeadingCDD(const Heading &heading)
Get the Heading value.
Definition: cdd_getters_common.h:131
getSpeed
double getSpeed(const CAM &cam)
Get the vehicle speed.
Definition: cam_getters_common.h:168
getSpeedConfidence
double getSpeedConfidence(const CAM &cam)
Get the Speed Confidence.
Definition: cam_getters_common.h:178
getSpecialTransportType
std::vector< bool > getSpecialTransportType(const SpecialTransportType &special_transport_type)
Get the Special Transport Type in form of bool vector.
Definition: cam_getters_common.h:323
getGenerationDeltaTime
GenerationDeltaTime getGenerationDeltaTime(const CAM &cam)
Get the GenerationDeltaTime.
Definition: cam_getters_common.h:51


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