cpm_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 
36 
38 
40 
50 inline void setItsPduHeader(CollectivePerceptionMessage& cpm, const uint32_t station_id,
51  const uint8_t protocol_version = 0) {
52  setItsPduHeader(cpm.header, MessageId::CPM, station_id, protocol_version);
53 }
54 
66 inline void setReferenceTime(
67  CollectivePerceptionMessage& cpm, const uint64_t unix_nanosecs,
68  const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
69  TimestampIts t_its;
70  setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
71  throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
72  cpm.payload.management_container.reference_time = t_its;
73 }
74 
86 inline void setReferencePosition(CollectivePerceptionMessage& cpm, const double latitude, const double longitude,
87  const double altitude = AltitudeValue::UNAVAILABLE) {
88  setReferencePosition(cpm.payload.management_container.reference_position, latitude, longitude, altitude);
89 }
90 
103 inline void setFromUTMPosition(CollectivePerceptionMessage& cpm, const gm::PointStamped& utm_position, const int& zone,
104  const bool& northp) {
105  setFromUTMPosition(cpm.payload.management_container.reference_position, utm_position, zone, northp);
106 }
107 
116 inline void setIdOfPerceivedObject(PerceivedObject& object, const uint16_t id) {
117  object.object_id.value = id;
118  object.object_id_is_present = true;
119 }
120 
132 inline void setMeasurementDeltaTimeOfPerceivedObject(PerceivedObject& object, const int16_t delta_time = 0) {
133  if (delta_time < DeltaTimeMilliSecondSigned::MIN || delta_time > DeltaTimeMilliSecondSigned::MAX) {
134  throw std::invalid_argument("MeasurementDeltaTime out of range");
135  } else {
136  object.measurement_delta_time.value = delta_time;
137  }
138 }
139 
153 inline void setCartesianCoordinateWithConfidence(CartesianCoordinateWithConfidence& coordinate, const double value,
154  const double confidence = std::numeric_limits<double>::infinity()) {
155  // limit value range
156  if (value < CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE) {
157  coordinate.value.value = CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE;
158  } else if (value > CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE) {
159  coordinate.value.value = CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE;
160  } else {
161  coordinate.value.value = static_cast<int32_t>(value);
162  }
163 
164  // limit confidence range
165  if (confidence == std::numeric_limits<double>::infinity()) {
166  coordinate.confidence.value = CoordinateConfidence::UNAVAILABLE;
167  } else if (confidence > CoordinateConfidence::MAX || confidence < CoordinateConfidence::MIN) {
168  coordinate.confidence.value = CoordinateConfidence::OUT_OF_RANGE;
169  } else {
170  coordinate.confidence.value = static_cast<uint16_t>(confidence);
171  }
172 }
173 
185 inline void setPositionOfPerceivedObject(PerceivedObject& object, const gm::Point& point,
186  const double x_std = std::numeric_limits<double>::infinity(),
187  const double y_std = std::numeric_limits<double>::infinity(),
188  const double z_std = std::numeric_limits<double>::infinity()) {
189  setCartesianCoordinateWithConfidence(object.position.x_coordinate, point.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
190  setCartesianCoordinateWithConfidence(object.position.y_coordinate, point.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
191  if (point.z != 0.0) {
192  setCartesianCoordinateWithConfidence(object.position.z_coordinate, point.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
193  object.position.z_coordinate_is_present = true;
194  }
195 }
196 
212 inline void setUTMPositionOfPerceivedObject(CollectivePerceptionMessage& cpm, PerceivedObject& object,
213  const gm::PointStamped& utm_position,
214  const double x_std = std::numeric_limits<double>::infinity(),
215  const double y_std = std::numeric_limits<double>::infinity(),
216  const double z_std = std::numeric_limits<double>::infinity()) {
217  gm::PointStamped reference_position = getUTMPosition(cpm);
218  if (utm_position.header.frame_id != reference_position.header.frame_id) {
219  throw std::invalid_argument("UTM-Position frame_id (" + utm_position.header.frame_id +
220  ") does not match the reference position frame_id (" + reference_position.header.frame_id +
221  ")");
222  }
223  setCartesianCoordinateWithConfidence(object.position.x_coordinate,
224  (utm_position.point.x - reference_position.point.x) * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
225  setCartesianCoordinateWithConfidence(object.position.y_coordinate,
226  (utm_position.point.y - reference_position.point.y) * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
227  if (utm_position.point.z != 0.0) {
228  setCartesianCoordinateWithConfidence(object.position.z_coordinate,
229  (utm_position.point.z - reference_position.point.z) * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
230  object.position.z_coordinate_is_present = true;
231  }
232 }
233 
245 inline void setVelocityComponent(VelocityComponent& velocity, const double value,
246  const double confidence = std::numeric_limits<double>::infinity()) {
247  // limit value range
248  if (value < VelocityComponentValue::NEGATIVE_OUT_OF_RANGE) {
249  velocity.value.value = VelocityComponentValue::NEGATIVE_OUT_OF_RANGE;
250  } else if (value > VelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
251  velocity.value.value = VelocityComponentValue::POSITIVE_OUT_OF_RANGE;
252  } else {
253  velocity.value.value = static_cast<int16_t>(value);
254  }
255 
256  // limit confidence range
257  if(confidence == std::numeric_limits<double>::infinity()) {
258  velocity.confidence.value = SpeedConfidence::UNAVAILABLE;
259  } else if (confidence > SpeedConfidence::MAX || confidence < SpeedConfidence::MIN) {
260  velocity.confidence.value = SpeedConfidence::OUT_OF_RANGE;
261  } else {
262  velocity.confidence.value = static_cast<uint8_t>(confidence);
263  }
264 }
265 
278 inline void setVelocityOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_velocity,
279  const double x_std = std::numeric_limits<double>::infinity(),
280  const double y_std = std::numeric_limits<double>::infinity(),
281  const double z_std = std::numeric_limits<double>::infinity()) {
282  object.velocity.choice = Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY;
283  setVelocityComponent(object.velocity.cartesian_velocity.x_velocity, cartesian_velocity.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
284  setVelocityComponent(object.velocity.cartesian_velocity.y_velocity, cartesian_velocity.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
285  if (cartesian_velocity.z != 0.0) {
286  setVelocityComponent(object.velocity.cartesian_velocity.z_velocity, cartesian_velocity.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
287  object.velocity.cartesian_velocity.z_velocity_is_present = true;
288  }
289  object.velocity_is_present = true;
290 }
291 
303 inline void setAccelerationComponent(AccelerationComponent& acceleration, const double value,
304  const double confidence = std::numeric_limits<double>::infinity()) {
305  // limit value range
306  if (value < AccelerationValue::NEGATIVE_OUT_OF_RANGE) {
307  acceleration.value.value = AccelerationValue::NEGATIVE_OUT_OF_RANGE;
308  } else if (value > AccelerationValue::POSITIVE_OUT_OF_RANGE) {
309  acceleration.value.value = AccelerationValue::POSITIVE_OUT_OF_RANGE;
310  } else {
311  acceleration.value.value = static_cast<int16_t>(value);
312  }
313 
314  // limit confidence range
315  if(confidence == std::numeric_limits<double>::infinity()) {
316  acceleration.confidence.value = AccelerationConfidence::UNAVAILABLE;
317  } else if (confidence > AccelerationConfidence::MAX || confidence < AccelerationConfidence::MIN) {
318  acceleration.confidence.value = AccelerationConfidence::OUT_OF_RANGE;
319  } else {
320  acceleration.confidence.value = static_cast<uint8_t>(confidence);
321  }
322 }
323 
336 inline void setAccelerationOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_acceleration,
337  const double x_std = std::numeric_limits<double>::infinity(),
338  const double y_std = std::numeric_limits<double>::infinity(),
339  const double z_std = std::numeric_limits<double>::infinity()) {
340  object.acceleration.choice = Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION;
341  setAccelerationComponent(object.acceleration.cartesian_acceleration.x_acceleration, cartesian_acceleration.x * 10,
343  setAccelerationComponent(object.acceleration.cartesian_acceleration.y_acceleration, cartesian_acceleration.y * 10,
345  if (cartesian_acceleration.z != 0.0) {
346  setAccelerationComponent(object.acceleration.cartesian_acceleration.z_acceleration, cartesian_acceleration.z * 10,
348  object.acceleration.cartesian_acceleration.z_acceleration_is_present = true;
349  }
350  object.acceleration_is_present = true;
351 }
352 
363 inline void setYawOfPerceivedObject(PerceivedObject& object, const double yaw,
364  double yaw_std = std::numeric_limits<double>::infinity()) {
365  // wrap angle to range [0, 360)
366  double yaw_in_degrees = yaw * 180 / M_PI;
367  while (yaw_in_degrees >= 360.0) yaw_in_degrees -= 360.0;
368  while (yaw_in_degrees < 0.0) yaw_in_degrees += 360.0;
369  object.angles.z_angle.value.value = yaw_in_degrees * 10;
370 
371  if(yaw_std == std::numeric_limits<double>::infinity()) {
372  object.angles.z_angle.confidence.value = AngleConfidence::UNAVAILABLE;
373  } else {
374  yaw_std *= 180.0 / M_PI;
375  yaw_std *= 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to 0.1 degrees
376 
377  if (yaw_std > AngleConfidence::MAX || yaw_std < AngleConfidence::MIN) {
378  object.angles.z_angle.confidence.value = AngleConfidence::OUT_OF_RANGE;
379  } else {
380  object.angles.z_angle.confidence.value = static_cast<uint8_t>(yaw_std);
381  }
382  }
383  object.angles_is_present = true;
384 }
385 
397 inline void setYawRateOfPerceivedObject(PerceivedObject& object, const double yaw_rate,
398  double yaw_rate_std = std::numeric_limits<double>::infinity()) {
399  double yaw_rate_in_degrees = yaw_rate * 180.0 / M_PI;
400  // limit value range
401  if (yaw_rate_in_degrees < CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE) {
402  yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE;
403  } else if (yaw_rate_in_degrees > CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
404  yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE;
405  }
406 
407  object.z_angular_velocity.value.value = yaw_rate_in_degrees;
408 
409  if(yaw_rate_std == std::numeric_limits<double>::infinity()) {
410  object.z_angular_velocity.confidence.value = AngularSpeedConfidence::UNAVAILABLE;
411  } else {
412  yaw_rate_std *= 180.0 / M_PI;
413  yaw_rate_std *= etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to degrees/s
414  // How stupid is this?!
415  static const std::map<double, uint8_t> confidence_map = {
416  {1.0, AngularSpeedConfidence::DEG_SEC_01},
417  {2.0, AngularSpeedConfidence::DEG_SEC_02},
418  {5.0, AngularSpeedConfidence::DEG_SEC_05},
419  {10.0, AngularSpeedConfidence::DEG_SEC_10},
420  {20.0, AngularSpeedConfidence::DEG_SEC_20},
421  {50.0, AngularSpeedConfidence::DEG_SEC_50},
422  {std::numeric_limits<double>::infinity(), AngularSpeedConfidence::OUT_OF_RANGE},
423  };
424  for(const auto& [thresh, conf_val] : confidence_map) {
425  if (yaw_rate_std <= thresh) {
426  object.z_angular_velocity.confidence.value = conf_val;
427  break;
428  }
429  }
430  }
431 
432  object.z_angular_velocity_is_present = true;
433 }
434 
449 inline void setObjectDimension(ObjectDimension& dimension, const double value,
450  const double confidence = std::numeric_limits<double>::infinity()) {
451  // limit value range
452  if (value < ObjectDimensionValue::MIN || value > ObjectDimensionValue::MAX) {
453  dimension.value.value = ObjectDimensionValue::OUT_OF_RANGE;
454  } else {
455  dimension.value.value = static_cast<uint16_t>(value);
456  }
457 
458  // limit confidence range
459  if (confidence == std::numeric_limits<double>::infinity()) {
460  dimension.confidence.value = ObjectDimensionConfidence::UNAVAILABLE;
461  } else if (confidence > ObjectDimensionConfidence::MAX || confidence < ObjectDimensionConfidence::MIN) {
462  dimension.confidence.value = ObjectDimensionConfidence::OUT_OF_RANGE;
463  } else {
464  dimension.confidence.value = static_cast<uint8_t>(confidence);
465  }
466 
467 }
468 
479 inline void setXDimensionOfPerceivedObject(PerceivedObject& object, const double value,
480  const double std = std::numeric_limits<double>::infinity()) {
481  setObjectDimension(object.object_dimension_x, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
482  object.object_dimension_x_is_present = true;
483 }
484 
495 inline void setYDimensionOfPerceivedObject(PerceivedObject& object, const double value,
496  const double std = std::numeric_limits<double>::infinity()) {
497  setObjectDimension(object.object_dimension_y, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
498  object.object_dimension_y_is_present = true;
499 }
500 
511 inline void setZDimensionOfPerceivedObject(PerceivedObject& object, const double value,
512  const double std = std::numeric_limits<double>::infinity()) {
513  setObjectDimension(object.object_dimension_z, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
514  object.object_dimension_z_is_present = true;
515 }
516 
528 inline void setDimensionsOfPerceivedObject(PerceivedObject& object, const gm::Vector3& dimensions,
529  const double x_std = std::numeric_limits<double>::infinity(),
530  const double y_std = std::numeric_limits<double>::infinity(),
531  const double z_std = std::numeric_limits<double>::infinity()) {
532  setXDimensionOfPerceivedObject(object, dimensions.x, x_std);
533  setYDimensionOfPerceivedObject(object, dimensions.y, y_std);
534  setZDimensionOfPerceivedObject(object, dimensions.z, z_std);
535 }
536 
546 inline void initPerceivedObject(PerceivedObject& object, const gm::Point& point, const int16_t delta_time = 0) {
547  setPositionOfPerceivedObject(object, point);
548  setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
549 }
550 
563 inline void initPerceivedObjectWithUTMPosition(CollectivePerceptionMessage& cpm, PerceivedObject& object,
564  const gm::PointStamped& point, const int16_t delta_time = 0) {
565  setUTMPositionOfPerceivedObject(cpm, object, point);
566  setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
567 }
568 
578 inline void initPerceivedObjectContainer(WrappedCpmContainer& container, const uint8_t n_objects = 0) {
579  container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER;
580  container.container_data_perceived_object_container.number_of_perceived_objects.value = n_objects;
581 }
582 
596 inline void addPerceivedObjectToContainer(WrappedCpmContainer& container, const PerceivedObject& perceived_object) {
597  if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER) {
598  container.container_data_perceived_object_container.perceived_objects.array.push_back(perceived_object);
599  container.container_data_perceived_object_container.number_of_perceived_objects.value =
600  container.container_data_perceived_object_container.perceived_objects.array.size();
601  } else {
602  throw std::invalid_argument("Container is not a PerceivedObjectContainer");
603  }
604 }
605 
618 inline void addContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
619  // check for maximum number of containers
620  if (cpm.payload.cpm_containers.value.array.size() < WrappedCpmContainers::MAX_SIZE) {
621  cpm.payload.cpm_containers.value.array.push_back(container);
622  } else {
623  throw std::invalid_argument("Maximum number of CPM-Containers reached");
624  }
625 }
626 
635 inline void setWGSRefPosConfidence(CollectivePerceptionMessage& cpm, const std::array<double, 4>& covariance_matrix) {
636  setWGSPosConfidenceEllipse(cpm.payload.management_container.reference_position.position_confidence_ellipse,
637  covariance_matrix);
638 }
639 
648 inline void initSensorInformationContainer(WrappedCpmContainer& container) {
649  container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER;
650  container.container_data_sensor_information_container.array = std::vector<SensorInformation>();
651 }
652 
663 inline void setSensorID(SensorInformation& sensor_information, const uint8_t sensor_id = 0) {
664  throwIfOutOfRange(sensor_id, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
665  sensor_information.sensor_id.value = sensor_id;
666 }
667 
678 inline void setSensorType(SensorInformation& sensor_information, const uint8_t sensor_type = SensorType::UNDEFINED) {
679  throwIfOutOfRange(sensor_type, SensorType::MIN, SensorType::MAX, "SensorType");
680  sensor_information.sensor_type.value = sensor_type;
681 }
682 
701 inline void addSensorInformationToContainer(WrappedCpmContainer& container, const SensorInformation& sensor_information) {
702  if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
703  // check for maximum number of SensorInformation entries
704  if (container.container_data_sensor_information_container.array.size() < SensorInformationContainer::MAX_SIZE ) {
705  throwIfOutOfRange(sensor_information.sensor_id.value, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
706  throwIfOutOfRange(sensor_information.sensor_type.value, SensorType::MIN, SensorType::MAX, "SensorType");
707  container.container_data_sensor_information_container.array.push_back(sensor_information);
708  } else {
709  throw std::invalid_argument("Maximum number of entries SensorInformationContainers reached");
710  }
711  } else {
712  throw std::invalid_argument("Container is not a SensorInformationContainer");
713  }
714 }
715 
730 inline void addSensorInformationContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
731  if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
732  throwIfOutOfRange(container.container_data_sensor_information_container.array.size(),
733  SensorInformationContainer::MIN_SIZE, SensorInformationContainer::MAX_SIZE, "SensorInformationContainer array size"
734  );
735  addContainerToCPM(cpm, container);
736  } else {
737  throw std::invalid_argument("Container is not a SensorInformationContainer");
738  }
739 }
740 
741 } // namespace etsi_its_cpm_ts_msgs::access
checks.h
Sanity-check functions etc.
etsi_its_cpm_ts_msgs::access::initPerceivedObjectWithUTMPosition
void initPerceivedObjectWithUTMPosition(CollectivePerceptionMessage &cpm, PerceivedObject &object, const gm::PointStamped &point, const int16_t delta_time=0)
Initializes a PerceivedObject with the given point (utm-position) and delta time.
Definition: cpm_ts_setters.h:563
etsi_its_cpm_ts_msgs::access::getUTMPosition
gm::PointStamped getUTMPosition(const CollectivePerceptionMessage &cpm, int &zone, bool &northp)
Get the UTM Position defined within the ManagementContainer of the CPM.
Definition: cpm_ts_getters.h:109
etsi_its_cpm_ts_msgs::access::setSensorType
void setSensorType(SensorInformation &sensor_information, const uint8_t sensor_type=SensorType::UNDEFINED)
Sets the sensorType of a SensorInformation object.
Definition: cpm_ts_setters.h:678
etsi_its_cpm_ts_msgs::access::setReferencePosition
void setReferencePosition(CollectivePerceptionMessage &cpm, const double latitude, const double longitude, const double altitude=AltitudeValue::UNAVAILABLE)
Set the ReferencePositionWithConfidence for a CPM TS.
Definition: cpm_ts_setters.h:86
etsi_its_cpm_ts_msgs::access::setUTMPositionOfPerceivedObject
void setUTMPositionOfPerceivedObject(CollectivePerceptionMessage &cpm, PerceivedObject &object, const gm::PointStamped &utm_position, const double x_std=std::numeric_limits< double >::infinity(), const double y_std=std::numeric_limits< double >::infinity(), const double z_std=std::numeric_limits< double >::infinity())
Sets the position of a perceived object based on a UTM position.
Definition: cpm_ts_setters.h:212
etsi_its_cpm_ts_msgs::access::setDimensionsOfPerceivedObject
void setDimensionsOfPerceivedObject(PerceivedObject &object, const gm::Vector3 &dimensions, const double x_std=std::numeric_limits< double >::infinity(), const double y_std=std::numeric_limits< double >::infinity(), const double z_std=std::numeric_limits< double >::infinity())
Sets all dimensions of a perceived object.
Definition: cpm_ts_setters.h:528
etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR
constexpr const double ONE_D_GAUSSIAN_FACTOR
Definition: constants.h:71
etsi_its_cpm_ts_msgs::access::setYDimensionOfPerceivedObject
void setYDimensionOfPerceivedObject(PerceivedObject &object, const double value, const double std=std::numeric_limits< double >::infinity())
Sets the y-dimension of a perceived object.
Definition: cpm_ts_setters.h:495
etsi_its_cpm_ts_msgs::access::setItsPduHeader
void setItsPduHeader(CollectivePerceptionMessage &cpm, const uint32_t station_id, const uint8_t protocol_version=0)
Sets the ITS PDU header of a CPM.
Definition: cpm_ts_setters.h:50
etsi_its_cpm_ts_msgs::access::setIdOfPerceivedObject
void setIdOfPerceivedObject(PerceivedObject &object, const uint16_t id)
Set the ID of a PerceivedObject.
Definition: cpm_ts_setters.h:116
etsi_its_cpm_ts_msgs::access::setYawOfPerceivedObject
void setYawOfPerceivedObject(PerceivedObject &object, const double yaw, double yaw_std=std::numeric_limits< double >::infinity())
Sets the yaw angle of a perceived object.
Definition: cpm_ts_setters.h:363
etsi_its_cpm_ts_msgs::access::addSensorInformationToContainer
void addSensorInformationToContainer(WrappedCpmContainer &container, const SensorInformation &sensor_information)
Adds a SensorInformation to the SensorInformationContainer / WrappedCpmContainer.
Definition: cpm_ts_setters.h:701
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
etsi_its_cpm_ts_msgs::access::initPerceivedObjectContainer
void initPerceivedObjectContainer(WrappedCpmContainer &container, const uint8_t n_objects=0)
Initializes a WrappedCpmContainer as a PerceivedObjectContainer with the given number of objects.
Definition: cpm_ts_setters.h:578
etsi_its_cpm_ts_msgs::access::addContainerToCPM
void addContainerToCPM(CollectivePerceptionMessage &cpm, const WrappedCpmContainer &container)
Adds a container to the Collective Perception Message (CPM).
Definition: cpm_ts_setters.h:618
etsi_its_cpm_ts_msgs::access::setZDimensionOfPerceivedObject
void setZDimensionOfPerceivedObject(PerceivedObject &object, const double value, const double std=std::numeric_limits< double >::infinity())
Sets the z-dimension of a perceived object.
Definition: cpm_ts_setters.h:511
etsi_its_cpm_ts_msgs::access::setMeasurementDeltaTimeOfPerceivedObject
void setMeasurementDeltaTimeOfPerceivedObject(PerceivedObject &object, const int16_t delta_time=0)
Sets the measurement delta time of a PerceivedObject.
Definition: cpm_ts_setters.h:132
etsi_its_cpm_ts_msgs::access::initSensorInformationContainer
void initSensorInformationContainer(WrappedCpmContainer &container)
Initializes a WrappedCpmContainer as a SensorInformationContainer.
Definition: cpm_ts_setters.h:648
etsi_its_cpm_ts_msgs::access::setReferenceTime
void setReferenceTime(CollectivePerceptionMessage &cpm, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin() ->second)
Sets the reference time in a CPM.
Definition: cpm_ts_setters.h:66
etsi_its_cpm_ts_msgs::access::setYawRateOfPerceivedObject
void setYawRateOfPerceivedObject(PerceivedObject &object, const double yaw_rate, double yaw_rate_std=std::numeric_limits< double >::infinity())
Sets the yaw rate of a perceived object.
Definition: cpm_ts_setters.h:397
etsi_its_cpm_ts_msgs::access::setFromUTMPosition
void setFromUTMPosition(CollectivePerceptionMessage &cpm, const gm::PointStamped &utm_position, const int &zone, const bool &northp)
Set the ReferencePosition of a CPM from a given UTM-Position.
Definition: cpm_ts_setters.h:103
etsi_its_cpm_ts_msgs::access::setWGSRefPosConfidence
void setWGSRefPosConfidence(CollectivePerceptionMessage &cpm, const std::array< double, 4 > &covariance_matrix)
Set the confidence of the reference position.
Definition: cpm_ts_setters.h:635
etsi_its_cpm_ts_msgs::access::setXDimensionOfPerceivedObject
void setXDimensionOfPerceivedObject(PerceivedObject &object, const double value, const double std=std::numeric_limits< double >::infinity())
Sets the x-dimension of a perceived object.
Definition: cpm_ts_setters.h:479
etsi_its_cpm_ts_msgs::access::setVelocityOfPerceivedObject
void setVelocityOfPerceivedObject(PerceivedObject &object, const gm::Vector3 &cartesian_velocity, const double x_std=std::numeric_limits< double >::infinity(), const double y_std=std::numeric_limits< double >::infinity(), const double z_std=std::numeric_limits< double >::infinity())
Definition: cpm_ts_setters.h:278
etsi_its_cpm_ts_msgs::access::setAccelerationComponent
void setAccelerationComponent(AccelerationComponent &acceleration, const double value, const double confidence=std::numeric_limits< double >::infinity())
Sets the value and confidence of a AccelerationComponent.
Definition: cpm_ts_setters.h:303
constants.h
File containing constants that are used in the context of ETIS ITS Messages.
std
etsi_its_cpm_ts_msgs::access::setSensorID
void setSensorID(SensorInformation &sensor_information, const uint8_t sensor_id=0)
Sets the sensorId of a SensorInformation object.
Definition: cpm_ts_setters.h:663
etsi_its_cpm_ts_msgs::access::addSensorInformationContainerToCPM
void addSensorInformationContainerToCPM(CollectivePerceptionMessage &cpm, const WrappedCpmContainer &container)
Adds a container to the Collective Perception Message (CPM).
Definition: cpm_ts_setters.h:730
etsi_its_cpm_ts_msgs::access::setVelocityComponent
void setVelocityComponent(VelocityComponent &velocity, const double value, const double confidence=std::numeric_limits< double >::infinity())
Sets the value and confidence of a VelocityComponent.
Definition: cpm_ts_setters.h:245
cdd_v2-1-1_setters.h
Setter functions for the ETSI ITS Common Data Dictionary (CDD) v2.1.1.
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
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
etsi_its_cpm_ts_msgs::access::addPerceivedObjectToContainer
void addPerceivedObjectToContainer(WrappedCpmContainer &container, const PerceivedObject &perceived_object)
Adds a PerceivedObject to the PerceivedObjectContainer / WrappedCpmContainer.
Definition: cpm_ts_setters.h:596
etsi_its_cpm_ts_msgs::access::setAccelerationOfPerceivedObject
void setAccelerationOfPerceivedObject(PerceivedObject &object, const gm::Vector3 &cartesian_acceleration, const double x_std=std::numeric_limits< double >::infinity(), const double y_std=std::numeric_limits< double >::infinity(), const double z_std=std::numeric_limits< double >::infinity())
Sets the acceleration of a perceived object.
Definition: cpm_ts_setters.h:336
etsi_its_cpm_ts_msgs::access::setPositionOfPerceivedObject
void setPositionOfPerceivedObject(PerceivedObject &object, const gm::Point &point, const double x_std=std::numeric_limits< double >::infinity(), const double y_std=std::numeric_limits< double >::infinity(), const double z_std=std::numeric_limits< double >::infinity())
Sets the position of a perceived object (relative to the CPM's reference position).
Definition: cpm_ts_setters.h:185
etsi_its_cpm_ts_msgs::access
Definition: impl/cpm/cpm_ts_access.h:52
etsi_its_cpm_ts_msgs::access::initPerceivedObject
void initPerceivedObject(PerceivedObject &object, const gm::Point &point, const int16_t delta_time=0)
Initializes a PerceivedObject with the given point and delta time.
Definition: cpm_ts_setters.h:546
etsi_its_cpm_ts_msgs::access::setCartesianCoordinateWithConfidence
void setCartesianCoordinateWithConfidence(CartesianCoordinateWithConfidence &coordinate, const double value, const double confidence=std::numeric_limits< double >::infinity())
Sets the value and confidence of a CartesianCoordinateWithConfidence object.
Definition: cpm_ts_setters.h:153
etsi_its_cpm_ts_msgs::access::setObjectDimension
void setObjectDimension(ObjectDimension &dimension, const double value, const double confidence=std::numeric_limits< double >::infinity())
Sets the object dimension with the given value and confidence.
Definition: cpm_ts_setters.h:449
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