etsi_its_messages v3.2.1
 
Loading...
Searching...
No Matches
cpm_ts_setters.h File Reference

Setter functions for the ETSI ITS CPM (TS) More...

Go to the source code of this file.

Classes

struct  etsi_its_cpm_ts_msgs::access::etsi_its_msgs::OneCentimeterHelper< SemiAxisLength, typename >
 
struct  etsi_its_cpm_ts_msgs::access::etsi_its_msgs::OneCentimeterHelper< SemiAxisLength, std::void_t< decltype(SemiAxisLength::ONE_CENTIMETER)> >
 

Functions

template<typename T1, typename T2>
void etsi_its_cpm_ts_msgs::access::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.
 
void etsi_its_cpm_ts_msgs::access::throwIfNotPresent (const bool is_present, const std::string val_desc)
 Throws an exception if the given value is not present.
 
uint16_t etsi_its_cpm_ts_msgs::access::etsi_its_msgs::getLeapSecondInsertionsSince2004 (const uint64_t unix_seconds)
 Get the leap second insertions since 2004 for given unix seconds.
 
void etsi_its_cpm_ts_msgs::access::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.
 
void etsi_its_cpm_ts_msgs::access::setLatitude (Latitude &latitude, const double deg)
 Set the Latitude object.
 
void etsi_its_cpm_ts_msgs::access::setLongitude (Longitude &longitude, const double deg)
 Set the Longitude object.
 
void etsi_its_cpm_ts_msgs::access::setAltitudeValue (AltitudeValue &altitude, const double value)
 Set the AltitudeValue object.
 
void etsi_its_cpm_ts_msgs::access::setAltitude (Altitude &altitude, const double value)
 Set the Altitude object.
 
void etsi_its_cpm_ts_msgs::access::setSpeedValue (SpeedValue &speed, const double value)
 Set the SpeedValue object.
 
void etsi_its_cpm_ts_msgs::access::setSpeedConfidence (SpeedConfidence &speed_confidence, const double value)
 Set the Speed Confidence object.
 
void etsi_its_cpm_ts_msgs::access::setSpeed (Speed &speed, const double value, const double confidence=std::numeric_limits< double >::infinity())
 Set the Speed object.
 
template<typename AccelerationConfidence>
void etsi_its_cpm_ts_msgs::access::setAccelerationConfidence (AccelerationConfidence &accel_confidence, const double value)
 Set the Acceleration Confidence object.
 
template<typename T>
void etsi_its_cpm_ts_msgs::access::setReferencePosition (T &ref_position, const double latitude, const double longitude, const double altitude=AltitudeValue::UNAVAILABLE)
 Sets the reference position in the given ReferencePostion object.
 
template<typename T>
void etsi_its_cpm_ts_msgs::access::setFromUTMPosition (T &reference_position, const gm::PointStamped &utm_position, const int zone, const bool northp)
 Set the ReferencePosition from a given UTM-Position.
 
template<typename HeadingValue>
void etsi_its_cpm_ts_msgs::access::setHeadingValue (HeadingValue &heading, const double value)
 Set the HeadingValue object.
 
template<typename HeadingConfidence>
void etsi_its_cpm_ts_msgs::access::setHeadingConfidence (HeadingConfidence &heading_confidence, const double value)
 Set the Heading Confidence object.
 
template<typename Heading, typename HeadingConfidence = decltype(Heading::heading_confidence)>
void etsi_its_cpm_ts_msgs::access::setHeadingCDD (Heading &heading, const double value, double confidence=std::numeric_limits< double >::infinity())
 Set the Heading object.
 
template<typename SemiAxisLength>
void etsi_its_cpm_ts_msgs::access::setSemiAxis (SemiAxisLength &semi_axis_length, const double length)
 Set the Semi Axis length.
 
template<typename PosConfidenceEllipse>
void etsi_its_cpm_ts_msgs::access::setPosConfidenceEllipse (PosConfidenceEllipse &position_confidence_ellipse, const double semi_major_axis, const double semi_minor_axis, const double orientation)
 Set the Pos Confidence Ellipse object.
 
std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::confidenceEllipseFromCovMatrix (const std::array< double, 4 > &covariance_matrix, const double object_heading)
 Gets the values needed to set a confidence ellipse from a covariance matrix.
 
std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::confidenceEllipseFromWGSCovMatrix (const std::array< double, 4 > &covariance_matrix)
 Gets the values needed to set a confidence ellipse from a covariance matrix.
 
template<typename PosConfidenceEllipse>
void etsi_its_cpm_ts_msgs::access::setPosConfidenceEllipse (PosConfidenceEllipse &position_confidence_ellipse, const std::array< double, 4 > &covariance_matrix, const double object_heading)
 Set the Pos Confidence Ellipse object.
 
template<typename PosConfidenceEllipse>
void etsi_its_cpm_ts_msgs::access::setWGSPosConfidenceEllipse (PosConfidenceEllipse &position_confidence_ellipse, const std::array< double, 4 > &covariance_matrix)
 Set the Pos Confidence Ellipse object.
 
void etsi_its_cpm_ts_msgs::access::setStationId (StationId &station_id, const uint32_t id_value)
 Set the Station Id object.
 
void etsi_its_cpm_ts_msgs::access::setItsPduHeader (ItsPduHeader &header, const uint8_t message_id, const uint32_t station_id, const uint8_t protocol_version=0)
 Set the Its Pdu Header object.
 
void etsi_its_cpm_ts_msgs::access::setStationType (TrafficParticipantType &station_type, const uint8_t value)
 Set the Station Type.
 
void etsi_its_cpm_ts_msgs::access::setLongitudinalAccelerationValue (AccelerationValue &accel, const double value)
 Set the LongitudinalAccelerationValue object.
 
void etsi_its_cpm_ts_msgs::access::setLongitudinalAcceleration (AccelerationComponent &accel, const double value, const double confidence)
 Set the LongitudinalAcceleration object.
 
void etsi_its_cpm_ts_msgs::access::setLateralAccelerationValue (AccelerationValue &accel, const double value)
 Set the LateralAccelerationValue object.
 
void etsi_its_cpm_ts_msgs::access::setLateralAcceleration (AccelerationComponent &accel, const double value, const double confidence)
 Set the LateralAcceleration object.
 
template<typename PositionConfidenceEllipse, typename Wgs84AngleValue = decltype(PositionConfidenceEllipse::semi_major_axis_orientation)>
void etsi_its_cpm_ts_msgs::access::setPositionConfidenceEllipse (PositionConfidenceEllipse &position_confidence_ellipse, const double semi_major_axis, const double semi_minor_axis, const double orientation)
 Set the Position Confidence Ellipse object.
 
template<typename PositionConfidenceEllipse>
void etsi_its_cpm_ts_msgs::access::setPositionConfidenceEllipse (PositionConfidenceEllipse &position_confidence_ellipse, const std::array< double, 4 > &covariance_matrix, const double object_heading)
 Set the Position Confidence Ellipse object.
 
template<typename PositionConfidenceEllipse>
void etsi_its_cpm_ts_msgs::access::setWGSPositionConfidenceEllipse (PositionConfidenceEllipse &position_confidence_ellipse, const std::array< double, 4 > &covariance_matrix)
 Set the Position Confidence Ellipse object.
 
void etsi_its_cpm_ts_msgs::access::setItsPduHeader (CollectivePerceptionMessage &cpm, const uint32_t station_id, const uint8_t protocol_version=0)
 Sets the ITS PDU header of a CPM.
 
void etsi_its_cpm_ts_msgs::access::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.
 
void etsi_its_cpm_ts_msgs::access::setReferencePosition (CollectivePerceptionMessage &cpm, const double latitude, const double longitude, const double altitude=AltitudeValue::UNAVAILABLE)
 Set the ReferencePositionWithConfidence for a CPM TS.
 
void etsi_its_cpm_ts_msgs::access::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.
 
void etsi_its_cpm_ts_msgs::access::setIdOfPerceivedObject (PerceivedObject &object, const uint16_t id)
 Set the ID of a PerceivedObject.
 
void etsi_its_cpm_ts_msgs::access::setMeasurementDeltaTimeOfPerceivedObject (PerceivedObject &object, const int16_t delta_time=0)
 Sets the measurement delta time of a PerceivedObject.
 
void etsi_its_cpm_ts_msgs::access::setCartesianCoordinateWithConfidence (CartesianCoordinateWithConfidence &coordinate, const double value, const double confidence=std::numeric_limits< double >::infinity())
 Sets the value and confidence of a CartesianCoordinateWithConfidence object.
 
void etsi_its_cpm_ts_msgs::access::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).
 
void etsi_its_cpm_ts_msgs::access::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.
 
void etsi_its_cpm_ts_msgs::access::setVelocityComponent (VelocityComponent &velocity, const double value, const double confidence=std::numeric_limits< double >::infinity())
 Sets the value and confidence of a VelocityComponent.
 
void etsi_its_cpm_ts_msgs::access::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())
 
void etsi_its_cpm_ts_msgs::access::setAccelerationComponent (AccelerationComponent &acceleration, const double value, const double confidence=std::numeric_limits< double >::infinity())
 Sets the value and confidence of a AccelerationComponent.
 
void etsi_its_cpm_ts_msgs::access::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.
 
void etsi_its_cpm_ts_msgs::access::setYawOfPerceivedObject (PerceivedObject &object, const double yaw, double yaw_std=std::numeric_limits< double >::infinity())
 Sets the yaw angle of a perceived object.
 
void etsi_its_cpm_ts_msgs::access::setYawRateOfPerceivedObject (PerceivedObject &object, const double yaw_rate, double yaw_rate_std=std::numeric_limits< double >::infinity())
 Sets the yaw rate of a perceived object.
 
void etsi_its_cpm_ts_msgs::access::setObjectDimension (ObjectDimension &dimension, const double value, const double confidence=std::numeric_limits< double >::infinity())
 Sets the object dimension with the given value and confidence.
 
void etsi_its_cpm_ts_msgs::access::setXDimensionOfPerceivedObject (PerceivedObject &object, const double value, const double std=std::numeric_limits< double >::infinity())
 Sets the x-dimension of a perceived object.
 
void etsi_its_cpm_ts_msgs::access::setYDimensionOfPerceivedObject (PerceivedObject &object, const double value, const double std=std::numeric_limits< double >::infinity())
 Sets the y-dimension of a perceived object.
 
void etsi_its_cpm_ts_msgs::access::setZDimensionOfPerceivedObject (PerceivedObject &object, const double value, const double std=std::numeric_limits< double >::infinity())
 Sets the z-dimension of a perceived object.
 
void etsi_its_cpm_ts_msgs::access::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.
 
void etsi_its_cpm_ts_msgs::access::initPerceivedObject (PerceivedObject &object, const gm::Point &point, const int16_t delta_time=0)
 Initializes a PerceivedObject with the given point and delta time.
 
void etsi_its_cpm_ts_msgs::access::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.
 
void etsi_its_cpm_ts_msgs::access::initPerceivedObjectContainer (WrappedCpmContainer &container, const uint8_t n_objects=0)
 Initializes a WrappedCpmContainer as a PerceivedObjectContainer with the given number of objects.
 
void etsi_its_cpm_ts_msgs::access::addPerceivedObjectToContainer (WrappedCpmContainer &container, const PerceivedObject &perceived_object)
 Adds a PerceivedObject to the PerceivedObjectContainer / WrappedCpmContainer.
 
void etsi_its_cpm_ts_msgs::access::addContainerToCPM (CollectivePerceptionMessage &cpm, const WrappedCpmContainer &container)
 Adds a container to the Collective Perception Message (CPM).
 
void etsi_its_cpm_ts_msgs::access::setWGSRefPosConfidence (CollectivePerceptionMessage &cpm, const std::array< double, 4 > &covariance_matrix)
 Set the confidence of the reference position.
 
void etsi_its_cpm_ts_msgs::access::initSensorInformationContainer (WrappedCpmContainer &container)
 Initializes a WrappedCpmContainer as a SensorInformationContainer.
 
void etsi_its_cpm_ts_msgs::access::setSensorID (SensorInformation &sensor_information, const uint8_t sensor_id=0)
 Sets the sensorId of a SensorInformation object.
 
void etsi_its_cpm_ts_msgs::access::setSensorType (SensorInformation &sensor_information, const uint8_t sensor_type=SensorType::UNDEFINED)
 Sets the sensorType of a SensorInformation object.
 
void etsi_its_cpm_ts_msgs::access::addSensorInformationToContainer (WrappedCpmContainer &container, const SensorInformation &sensor_information)
 Adds a SensorInformation to the SensorInformationContainer / WrappedCpmContainer.
 
void etsi_its_cpm_ts_msgs::access::addSensorInformationContainerToCPM (CollectivePerceptionMessage &cpm, const WrappedCpmContainer &container)
 Adds a container to the Collective Perception Message (CPM).
 

Variables

const uint64_t etsi_its_cpm_ts_msgs::access::etsi_its_msgs::UNIX_SECONDS_2004 = 1072915200
 
const std::map< uint64_t, uint16_t > etsi_its_cpm_ts_msgs::access::etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004
 std::map that stores all leap second insertions since 2004 with the corresponding unix-date of the insertion
 
constexpr const double etsi_its_cpm_ts_msgs::access::etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR = 2.0
 
constexpr const double etsi_its_cpm_ts_msgs::access::etsi_its_msgs::TWO_D_GAUSSIAN_FACTOR = 2.4477
 

Detailed Description

Setter functions for the ETSI ITS CPM (TS)

Definition in file cpm_ts_setters.h.

Function Documentation

◆ addContainerToCPM()

void etsi_its_cpm_ts_msgs::access::addContainerToCPM ( CollectivePerceptionMessage & cpm,
const WrappedCpmContainer & container )
inline

Adds a container to the Collective Perception Message (CPM).

This function adds a WrappedCpmContainer to the CPM's payload. It first checks if the current number of containers is less than the maximum allowed. If so, it appends the container to the array. Otherwise, it throws an exception.

Parameters
cpmThe Collective Perception Message to which the container will be added.
containerThe WrappedCpmContainer to be added to the CPM.
Exceptions
std::invalid_argumentif the maximum number of CPM-Containers is reached.

Definition at line 790 of file cpm_ts_setters.h.

◆ addPerceivedObjectToContainer()

void etsi_its_cpm_ts_msgs::access::addPerceivedObjectToContainer ( WrappedCpmContainer & container,
const PerceivedObject & perceived_object )
inline

Adds a PerceivedObject to the PerceivedObjectContainer / WrappedCpmContainer.

This function checks if the provided container is a PerceivedObjectContainer. If it is, the function adds the given PerceivedObject to the container's perceived_objects array and updates the number_of_perceived_objects value. If the container is not a PerceivedObjectContainer, the function throws an std::invalid_argument exception.

Parameters
containerThe WrappedCpmContainer to which the PerceivedObject will be added.
perceived_objectThe PerceivedObject to add to the container.
Exceptions
std::invalid_argumentif the container is not a PerceivedObjectContainer.

Definition at line 768 of file cpm_ts_setters.h.

804 {
805
807
817inline void setItsPduHeader(CollectivePerceptionMessage& cpm, const uint32_t station_id,
818 const uint8_t protocol_version = 0) {
819 setItsPduHeader(cpm.header, MessageId::CPM, station_id, protocol_version);
820}
821
833inline void setReferenceTime(
834 CollectivePerceptionMessage& cpm, const uint64_t unix_nanosecs,
835 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
836 TimestampIts t_its;
837 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
838 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
839 cpm.payload.management_container.reference_time = t_its;
840}
841
853inline void setReferencePosition(CollectivePerceptionMessage& cpm, const double latitude, const double longitude,
854 const double altitude = AltitudeValue::UNAVAILABLE) {
855 setReferencePosition(cpm.payload.management_container.reference_position, latitude, longitude, altitude);
856}
857
870inline void setFromUTMPosition(CollectivePerceptionMessage& cpm, const gm::PointStamped& utm_position, const int& zone,
871 const bool& northp) {
872 setFromUTMPosition(cpm.payload.management_container.reference_position, utm_position, zone, northp);
873}
874
883inline void setIdOfPerceivedObject(PerceivedObject& object, const uint16_t id) {
884 object.object_id.value = id;
885 object.object_id_is_present = true;
886}
887
899inline void setMeasurementDeltaTimeOfPerceivedObject(PerceivedObject& object, const int16_t delta_time = 0) {
900 if (delta_time < DeltaTimeMilliSecondSigned::MIN || delta_time > DeltaTimeMilliSecondSigned::MAX) {
901 throw std::invalid_argument("MeasurementDeltaTime out of range");
902 } else {
903 object.measurement_delta_time.value = delta_time;
904 }
905}
906
920inline void setCartesianCoordinateWithConfidence(CartesianCoordinateWithConfidence& coordinate, const double value,
921 const double confidence = std::numeric_limits<double>::infinity()) {
922 // limit value range
923 if (value < CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE) {
924 coordinate.value.value = CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE;
925 } else if (value > CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE) {
926 coordinate.value.value = CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE;
927 } else {
928 coordinate.value.value = static_cast<int32_t>(value);
929 }
930
931 // limit confidence range
932 if (confidence == std::numeric_limits<double>::infinity()) {
933 coordinate.confidence.value = CoordinateConfidence::UNAVAILABLE;
934 } else if (confidence > CoordinateConfidence::MAX || confidence < CoordinateConfidence::MIN) {
935 coordinate.confidence.value = CoordinateConfidence::OUT_OF_RANGE;
936 } else {
937 coordinate.confidence.value = static_cast<uint16_t>(confidence);
938 }
939}
940
952inline void setPositionOfPerceivedObject(PerceivedObject& object, const gm::Point& point,
953 const double x_std = std::numeric_limits<double>::infinity(),
954 const double y_std = std::numeric_limits<double>::infinity(),
955 const double z_std = std::numeric_limits<double>::infinity()) {
956 setCartesianCoordinateWithConfidence(object.position.x_coordinate, point.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
957 setCartesianCoordinateWithConfidence(object.position.y_coordinate, point.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
958 if (point.z != 0.0) {
959 setCartesianCoordinateWithConfidence(object.position.z_coordinate, point.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
960 object.position.z_coordinate_is_present = true;
961 }
962}
963
979inline void setUTMPositionOfPerceivedObject(CollectivePerceptionMessage& cpm, PerceivedObject& object,
980 const gm::PointStamped& utm_position,
981 const double x_std = std::numeric_limits<double>::infinity(),
982 const double y_std = std::numeric_limits<double>::infinity(),
983 const double z_std = std::numeric_limits<double>::infinity()) {
984 gm::PointStamped reference_position = getUTMPosition(cpm);
985 if (utm_position.header.frame_id != reference_position.header.frame_id) {
986 throw std::invalid_argument("UTM-Position frame_id (" + utm_position.header.frame_id +
987 ") does not match the reference position frame_id (" + reference_position.header.frame_id +
988 ")");
989 }
990 setCartesianCoordinateWithConfidence(object.position.x_coordinate,
991 (utm_position.point.x - reference_position.point.x) * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
992 setCartesianCoordinateWithConfidence(object.position.y_coordinate,
993 (utm_position.point.y - reference_position.point.y) * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
994 if (utm_position.point.z != 0.0) {
995 setCartesianCoordinateWithConfidence(object.position.z_coordinate,
996 (utm_position.point.z - reference_position.point.z) * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
997 object.position.z_coordinate_is_present = true;
998 }
999}
1000
1012inline void setVelocityComponent(VelocityComponent& velocity, const double value,
1013 const double confidence = std::numeric_limits<double>::infinity()) {
1014 // limit value range
1015 if (value < VelocityComponentValue::NEGATIVE_OUT_OF_RANGE) {
1016 velocity.value.value = VelocityComponentValue::NEGATIVE_OUT_OF_RANGE;
1017 } else if (value > VelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1018 velocity.value.value = VelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1019 } else {
1020 velocity.value.value = static_cast<int16_t>(value);
1021 }
1022
1023 // limit confidence range
1024 if(confidence == std::numeric_limits<double>::infinity()) {
1025 velocity.confidence.value = SpeedConfidence::UNAVAILABLE;
1026 } else if (confidence > SpeedConfidence::MAX || confidence < SpeedConfidence::MIN) {
1027 velocity.confidence.value = SpeedConfidence::OUT_OF_RANGE;
1028 } else {
1029 velocity.confidence.value = static_cast<uint8_t>(confidence);
1030 }
1031}
1032
1045inline void setVelocityOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_velocity,
1046 const double x_std = std::numeric_limits<double>::infinity(),
1047 const double y_std = std::numeric_limits<double>::infinity(),
1048 const double z_std = std::numeric_limits<double>::infinity()) {
1049 object.velocity.choice = Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY;
1050 setVelocityComponent(object.velocity.cartesian_velocity.x_velocity, cartesian_velocity.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1051 setVelocityComponent(object.velocity.cartesian_velocity.y_velocity, cartesian_velocity.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1052 if (cartesian_velocity.z != 0.0) {
1053 setVelocityComponent(object.velocity.cartesian_velocity.z_velocity, cartesian_velocity.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1054 object.velocity.cartesian_velocity.z_velocity_is_present = true;
1055 }
1056 object.velocity_is_present = true;
1057}
1058
1070inline void setAccelerationComponent(AccelerationComponent& acceleration, const double value,
1071 const double confidence = std::numeric_limits<double>::infinity()) {
1072 // limit value range
1073 if (value < AccelerationValue::NEGATIVE_OUT_OF_RANGE) {
1074 acceleration.value.value = AccelerationValue::NEGATIVE_OUT_OF_RANGE;
1075 } else if (value > AccelerationValue::POSITIVE_OUT_OF_RANGE) {
1076 acceleration.value.value = AccelerationValue::POSITIVE_OUT_OF_RANGE;
1077 } else {
1078 acceleration.value.value = static_cast<int16_t>(value);
1079 }
1080
1081 // limit confidence range
1082 if(confidence == std::numeric_limits<double>::infinity()) {
1083 acceleration.confidence.value = AccelerationConfidence::UNAVAILABLE;
1084 } else if (confidence > AccelerationConfidence::MAX || confidence < AccelerationConfidence::MIN) {
1085 acceleration.confidence.value = AccelerationConfidence::OUT_OF_RANGE;
1086 } else {
1087 acceleration.confidence.value = static_cast<uint8_t>(confidence);
1088 }
1089}
1090
1103inline void setAccelerationOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_acceleration,
1104 const double x_std = std::numeric_limits<double>::infinity(),
1105 const double y_std = std::numeric_limits<double>::infinity(),
1106 const double z_std = std::numeric_limits<double>::infinity()) {
1107 object.acceleration.choice = Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION;
1108 setAccelerationComponent(object.acceleration.cartesian_acceleration.x_acceleration, cartesian_acceleration.x * 10,
1109 x_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1110 setAccelerationComponent(object.acceleration.cartesian_acceleration.y_acceleration, cartesian_acceleration.y * 10,
1111 y_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1112 if (cartesian_acceleration.z != 0.0) {
1113 setAccelerationComponent(object.acceleration.cartesian_acceleration.z_acceleration, cartesian_acceleration.z * 10,
1114 z_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1115 object.acceleration.cartesian_acceleration.z_acceleration_is_present = true;
1116 }
1117 object.acceleration_is_present = true;
1118}
1119
1130inline void setYawOfPerceivedObject(PerceivedObject& object, const double yaw,
1131 double yaw_std = std::numeric_limits<double>::infinity()) {
1132 // wrap angle to range [0, 360)
1133 double yaw_in_degrees = yaw * 180 / M_PI;
1134 while (yaw_in_degrees >= 360.0) yaw_in_degrees -= 360.0;
1135 while (yaw_in_degrees < 0.0) yaw_in_degrees += 360.0;
1136 object.angles.z_angle.value.value = yaw_in_degrees * 10;
1137
1138 if(yaw_std == std::numeric_limits<double>::infinity()) {
1139 object.angles.z_angle.confidence.value = AngleConfidence::UNAVAILABLE;
1140 } else {
1141 yaw_std *= 180.0 / M_PI;
1142 yaw_std *= 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to 0.1 degrees
1143
1144 if (yaw_std > AngleConfidence::MAX || yaw_std < AngleConfidence::MIN) {
1145 object.angles.z_angle.confidence.value = AngleConfidence::OUT_OF_RANGE;
1146 } else {
1147 object.angles.z_angle.confidence.value = static_cast<uint8_t>(yaw_std);
1148 }
1149 }
1150 object.angles_is_present = true;
1151}
1152
1164inline void setYawRateOfPerceivedObject(PerceivedObject& object, const double yaw_rate,
1165 double yaw_rate_std = std::numeric_limits<double>::infinity()) {
1166 double yaw_rate_in_degrees = yaw_rate * 180.0 / M_PI;
1167 // limit value range
1168 if (yaw_rate_in_degrees < CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE) {
1169 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE;
1170 } else if (yaw_rate_in_degrees > CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1171 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1172 }
1173
1174 object.z_angular_velocity.value.value = yaw_rate_in_degrees;
1175
1176 if(yaw_rate_std == std::numeric_limits<double>::infinity()) {
1177 object.z_angular_velocity.confidence.value = AngularSpeedConfidence::UNAVAILABLE;
1178 } else {
1179 yaw_rate_std *= 180.0 / M_PI;
1180 yaw_rate_std *= etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to degrees/s
1181 // How stupid is this?!
1182 static const std::map<double, uint8_t> confidence_map = {
1183 {1.0, AngularSpeedConfidence::DEG_SEC_01},
1184 {2.0, AngularSpeedConfidence::DEG_SEC_02},
1185 {5.0, AngularSpeedConfidence::DEG_SEC_05},
1186 {10.0, AngularSpeedConfidence::DEG_SEC_10},
1187 {20.0, AngularSpeedConfidence::DEG_SEC_20},
1188 {50.0, AngularSpeedConfidence::DEG_SEC_50},
1189 {std::numeric_limits<double>::infinity(), AngularSpeedConfidence::OUT_OF_RANGE},
1190 };
1191 for(const auto& [thresh, conf_val] : confidence_map) {
1192 if (yaw_rate_std <= thresh) {
1193 object.z_angular_velocity.confidence.value = conf_val;
1194 break;
1195 }
1196 }
1197 }
1198
1199 object.z_angular_velocity_is_present = true;
1200}
1201
1216inline void setObjectDimension(ObjectDimension& dimension, const double value,
1217 const double confidence = std::numeric_limits<double>::infinity()) {
1218 // limit value range
1219 if (value < ObjectDimensionValue::MIN || value > ObjectDimensionValue::MAX) {
1220 dimension.value.value = ObjectDimensionValue::OUT_OF_RANGE;
1221 } else {
1222 dimension.value.value = static_cast<uint16_t>(value);
1223 }
1224
1225 // limit confidence range
1226 if (confidence == std::numeric_limits<double>::infinity()) {
1227 dimension.confidence.value = ObjectDimensionConfidence::UNAVAILABLE;
1228 } else if (confidence > ObjectDimensionConfidence::MAX || confidence < ObjectDimensionConfidence::MIN) {
1229 dimension.confidence.value = ObjectDimensionConfidence::OUT_OF_RANGE;
1230 } else {
1231 dimension.confidence.value = static_cast<uint8_t>(confidence);
1232 }
1233
1234}
1235
1246inline void setXDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1247 const double std = std::numeric_limits<double>::infinity()) {
1248 setObjectDimension(object.object_dimension_x, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1249 object.object_dimension_x_is_present = true;
1250}
1251
1262inline void setYDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1263 const double std = std::numeric_limits<double>::infinity()) {
1264 setObjectDimension(object.object_dimension_y, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1265 object.object_dimension_y_is_present = true;
1266}
1267
1278inline void setZDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1279 const double std = std::numeric_limits<double>::infinity()) {
1280 setObjectDimension(object.object_dimension_z, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1281 object.object_dimension_z_is_present = true;
1282}
1283
1295inline void setDimensionsOfPerceivedObject(PerceivedObject& object, const gm::Vector3& dimensions,
1296 const double x_std = std::numeric_limits<double>::infinity(),
1297 const double y_std = std::numeric_limits<double>::infinity(),
1298 const double z_std = std::numeric_limits<double>::infinity()) {
1299 setXDimensionOfPerceivedObject(object, dimensions.x, x_std);
1300 setYDimensionOfPerceivedObject(object, dimensions.y, y_std);
1301 setZDimensionOfPerceivedObject(object, dimensions.z, z_std);
1302}
1303
1313inline void initPerceivedObject(PerceivedObject& object, const gm::Point& point, const int16_t delta_time = 0) {
1314 setPositionOfPerceivedObject(object, point);
1315 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1316}
1317
1330inline void initPerceivedObjectWithUTMPosition(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1331 const gm::PointStamped& point, const int16_t delta_time = 0) {
1332 setUTMPositionOfPerceivedObject(cpm, object, point);
1333 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1334}
1335
1345inline void initPerceivedObjectContainer(WrappedCpmContainer& container, const uint8_t n_objects = 0) {
1346 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER;
1347 container.container_data_perceived_object_container.number_of_perceived_objects.value = n_objects;
1348}
1349
1363inline void addPerceivedObjectToContainer(WrappedCpmContainer& container, const PerceivedObject& perceived_object) {
1364 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER) {
1365 container.container_data_perceived_object_container.perceived_objects.array.push_back(perceived_object);
1366 container.container_data_perceived_object_container.number_of_perceived_objects.value =
1367 container.container_data_perceived_object_container.perceived_objects.array.size();
1368 } else {
1369 throw std::invalid_argument("Container is not a PerceivedObjectContainer");
1370 }
1371}
1372
1385inline void addContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1386 // check for maximum number of containers
1387 if (cpm.payload.cpm_containers.value.array.size() < WrappedCpmContainers::MAX_SIZE) {
1388 cpm.payload.cpm_containers.value.array.push_back(container);
1389 } else {
1390 throw std::invalid_argument("Maximum number of CPM-Containers reached");
1391 }
1392}
1393
1402inline void setWGSRefPosConfidence(CollectivePerceptionMessage& cpm, const std::array<double, 4>& covariance_matrix) {
1403 setWGSPosConfidenceEllipse(cpm.payload.management_container.reference_position.position_confidence_ellipse,
1404 covariance_matrix);
1405}
1406
1415inline void initSensorInformationContainer(WrappedCpmContainer& container) {
1416 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER;
1417 container.container_data_sensor_information_container.array = std::vector<SensorInformation>();
1418}
1419
1430inline void setSensorID(SensorInformation& sensor_information, const uint8_t sensor_id = 0) {
1431 throwIfOutOfRange(sensor_id, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1432 sensor_information.sensor_id.value = sensor_id;
1433}
1434
1445inline void setSensorType(SensorInformation& sensor_information, const uint8_t sensor_type = SensorType::UNDEFINED) {
1446 throwIfOutOfRange(sensor_type, SensorType::MIN, SensorType::MAX, "SensorType");
1447 sensor_information.sensor_type.value = sensor_type;
1448}
1449
1468inline void addSensorInformationToContainer(WrappedCpmContainer& container, const SensorInformation& sensor_information) {
1469 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1470 // check for maximum number of SensorInformation entries
1471 if (container.container_data_sensor_information_container.array.size() < SensorInformationContainer::MAX_SIZE ) {
1472 throwIfOutOfRange(sensor_information.sensor_id.value, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1473 throwIfOutOfRange(sensor_information.sensor_type.value, SensorType::MIN, SensorType::MAX, "SensorType");
1474 container.container_data_sensor_information_container.array.push_back(sensor_information);
1475 } else {
1476 throw std::invalid_argument("Maximum number of entries SensorInformationContainers reached");
1477 }
1478 } else {
1479 throw std::invalid_argument("Container is not a SensorInformationContainer");
1480 }
1481}
1482
1497inline void addSensorInformationContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1498 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1499 throwIfOutOfRange(container.container_data_sensor_information_container.array.size(),
1500 SensorInformationContainer::MIN_SIZE, SensorInformationContainer::MAX_SIZE, "SensorInformationContainer array size"
1501 );
1502 addContainerToCPM(cpm, container);
1503 } else {
1504 throw std::invalid_argument("Container is not a SensorInformationContainer");
1505 }
1506}
1507
1508} // namespace etsi_its_cpm_ts_msgs::access
void setReferencePosition(CAM &cam, const double latitude, const double longitude, const double altitude=AltitudeValue::UNAVAILABLE)
Set the ReferencePosition for a CAM.
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.
Setter functions for the ETSI ITS Common Data Dictionary (CDD) v2.1.1.
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
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
gm::PointStamped getUTMPosition(const T &reference_position, int &zone, bool &northp)
Get the UTM Position defined by the given ReferencePosition.
void addSensorInformationToContainer(WrappedCpmContainer &container, const SensorInformation &sensor_information)
Adds a SensorInformation to the SensorInformationContainer / WrappedCpmContainer.
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())
void setWGSPosConfidenceEllipse(PosConfidenceEllipse &position_confidence_ellipse, const std::array< double, 4 > &covariance_matrix)
Set the Pos Confidence Ellipse object.
void setAccelerationComponent(AccelerationComponent &acceleration, const double value, const double confidence=std::numeric_limits< double >::infinity())
Sets the value and confidence of a AccelerationComponent.
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.
void initPerceivedObjectContainer(WrappedCpmContainer &container, const uint8_t n_objects=0)
Initializes a WrappedCpmContainer as a PerceivedObjectContainer with the given number of objects.
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.
void setYDimensionOfPerceivedObject(PerceivedObject &object, const double value, const double std=std::numeric_limits< double >::infinity())
Sets the y-dimension of a perceived object.
void addSensorInformationContainerToCPM(CollectivePerceptionMessage &cpm, const WrappedCpmContainer &container)
Adds a container to the Collective Perception Message (CPM).
void setWGSRefPosConfidence(CollectivePerceptionMessage &cpm, const std::array< double, 4 > &covariance_matrix)
Set the confidence of the reference position.
void setVelocityComponent(VelocityComponent &velocity, const double value, const double confidence=std::numeric_limits< double >::infinity())
Sets the value and confidence of a VelocityComponent.
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.
void setItsPduHeader(ItsPduHeader &header, const uint8_t message_id, const uint32_t station_id, const uint8_t protocol_version=0)
Set the Its Pdu Header object.
void setFromUTMPosition(T &reference_position, const gm::PointStamped &utm_position, const int zone, const bool northp)
Set the ReferencePosition from a given UTM-Position.
void setYawOfPerceivedObject(PerceivedObject &object, const double yaw, double yaw_std=std::numeric_limits< double >::infinity())
Sets the yaw angle of a perceived object.
void addPerceivedObjectToContainer(WrappedCpmContainer &container, const PerceivedObject &perceived_object)
Adds a PerceivedObject to the PerceivedObjectContainer / WrappedCpmContainer.
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.
void addContainerToCPM(CollectivePerceptionMessage &cpm, const WrappedCpmContainer &container)
Adds a container to the Collective Perception Message (CPM).
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.
void setIdOfPerceivedObject(PerceivedObject &object, const uint16_t id)
Set the ID of a PerceivedObject.
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.
void setXDimensionOfPerceivedObject(PerceivedObject &object, const double value, const double std=std::numeric_limits< double >::infinity())
Sets the x-dimension of a perceived object.
void setZDimensionOfPerceivedObject(PerceivedObject &object, const double value, const double std=std::numeric_limits< double >::infinity())
Sets the z-dimension of a perceived object.
void setCartesianCoordinateWithConfidence(CartesianCoordinateWithConfidence &coordinate, const double value, const double confidence=std::numeric_limits< double >::infinity())
Sets the value and confidence of a CartesianCoordinateWithConfidence object.
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).
void setMeasurementDeltaTimeOfPerceivedObject(PerceivedObject &object, const int16_t delta_time=0)
Sets the measurement delta time of a PerceivedObject.
void setSensorType(SensorInformation &sensor_information, const uint8_t sensor_type=SensorType::UNDEFINED)
Sets the sensorType of a SensorInformation object.
void initSensorInformationContainer(WrappedCpmContainer &container)
Initializes a WrappedCpmContainer as a SensorInformationContainer.
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.
void setSensorID(SensorInformation &sensor_information, const uint8_t sensor_id=0)
Sets the sensorId of a SensorInformation object.
void initPerceivedObject(PerceivedObject &object, const gm::Point &point, const int16_t delta_time=0)
Initializes a PerceivedObject with the given point and delta time.

◆ addSensorInformationContainerToCPM()

void etsi_its_cpm_ts_msgs::access::addSensorInformationContainerToCPM ( CollectivePerceptionMessage & cpm,
const WrappedCpmContainer & container )
inline

Adds a container to the Collective Perception Message (CPM).

This function adds a SensorInformationContainer / WrappedCpmContainer to the CPM's payload. It first checks if the container is a SensorInformationContainer. If so, it checks if the number of entries is in the allowed range. If the number of entries is valid, it appends the container to the array. Otherwise, it throws an exception.

Parameters
cpmThe Collective Perception Message to which the container will be added.
containerThe WrappedCpmContainer to be added to the CPM.
Exceptions
std::invalid_argumentif the container is not a SensorInformationContainer.
std::invalid_argumentif the number of SensorInformation entries is out of range.

Definition at line 902 of file cpm_ts_setters.h.

938 {
939
941
951inline void setItsPduHeader(CollectivePerceptionMessage& cpm, const uint32_t station_id,
952 const uint8_t protocol_version = 0) {
953 setItsPduHeader(cpm.header, MessageId::CPM, station_id, protocol_version);
954}
955
967inline void setReferenceTime(
968 CollectivePerceptionMessage& cpm, const uint64_t unix_nanosecs,
969 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
970 TimestampIts t_its;
971 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
972 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
973 cpm.payload.management_container.reference_time = t_its;
974}
975
987inline void setReferencePosition(CollectivePerceptionMessage& cpm, const double latitude, const double longitude,
988 const double altitude = AltitudeValue::UNAVAILABLE) {
989 setReferencePosition(cpm.payload.management_container.reference_position, latitude, longitude, altitude);
990}
991
1004inline void setFromUTMPosition(CollectivePerceptionMessage& cpm, const gm::PointStamped& utm_position, const int& zone,
1005 const bool& northp) {
1006 setFromUTMPosition(cpm.payload.management_container.reference_position, utm_position, zone, northp);
1007}
1008
1017inline void setIdOfPerceivedObject(PerceivedObject& object, const uint16_t id) {
1018 object.object_id.value = id;
1019 object.object_id_is_present = true;
1020}
1021
1033inline void setMeasurementDeltaTimeOfPerceivedObject(PerceivedObject& object, const int16_t delta_time = 0) {
1034 if (delta_time < DeltaTimeMilliSecondSigned::MIN || delta_time > DeltaTimeMilliSecondSigned::MAX) {
1035 throw std::invalid_argument("MeasurementDeltaTime out of range");
1036 } else {
1037 object.measurement_delta_time.value = delta_time;
1038 }
1039}
1040
1054inline void setCartesianCoordinateWithConfidence(CartesianCoordinateWithConfidence& coordinate, const double value,
1055 const double confidence = std::numeric_limits<double>::infinity()) {
1056 // limit value range
1057 if (value < CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE) {
1058 coordinate.value.value = CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE;
1059 } else if (value > CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE) {
1060 coordinate.value.value = CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE;
1061 } else {
1062 coordinate.value.value = static_cast<int32_t>(value);
1063 }
1064
1065 // limit confidence range
1066 if (confidence == std::numeric_limits<double>::infinity()) {
1067 coordinate.confidence.value = CoordinateConfidence::UNAVAILABLE;
1068 } else if (confidence > CoordinateConfidence::MAX || confidence < CoordinateConfidence::MIN) {
1069 coordinate.confidence.value = CoordinateConfidence::OUT_OF_RANGE;
1070 } else {
1071 coordinate.confidence.value = static_cast<uint16_t>(confidence);
1072 }
1073}
1074
1086inline void setPositionOfPerceivedObject(PerceivedObject& object, const gm::Point& point,
1087 const double x_std = std::numeric_limits<double>::infinity(),
1088 const double y_std = std::numeric_limits<double>::infinity(),
1089 const double z_std = std::numeric_limits<double>::infinity()) {
1090 setCartesianCoordinateWithConfidence(object.position.x_coordinate, point.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1091 setCartesianCoordinateWithConfidence(object.position.y_coordinate, point.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1092 if (point.z != 0.0) {
1093 setCartesianCoordinateWithConfidence(object.position.z_coordinate, point.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1094 object.position.z_coordinate_is_present = true;
1095 }
1096}
1097
1113inline void setUTMPositionOfPerceivedObject(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1114 const gm::PointStamped& utm_position,
1115 const double x_std = std::numeric_limits<double>::infinity(),
1116 const double y_std = std::numeric_limits<double>::infinity(),
1117 const double z_std = std::numeric_limits<double>::infinity()) {
1118 gm::PointStamped reference_position = getUTMPosition(cpm);
1119 if (utm_position.header.frame_id != reference_position.header.frame_id) {
1120 throw std::invalid_argument("UTM-Position frame_id (" + utm_position.header.frame_id +
1121 ") does not match the reference position frame_id (" + reference_position.header.frame_id +
1122 ")");
1123 }
1124 setCartesianCoordinateWithConfidence(object.position.x_coordinate,
1125 (utm_position.point.x - reference_position.point.x) * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1126 setCartesianCoordinateWithConfidence(object.position.y_coordinate,
1127 (utm_position.point.y - reference_position.point.y) * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1128 if (utm_position.point.z != 0.0) {
1129 setCartesianCoordinateWithConfidence(object.position.z_coordinate,
1130 (utm_position.point.z - reference_position.point.z) * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1131 object.position.z_coordinate_is_present = true;
1132 }
1133}
1134
1146inline void setVelocityComponent(VelocityComponent& velocity, const double value,
1147 const double confidence = std::numeric_limits<double>::infinity()) {
1148 // limit value range
1149 if (value < VelocityComponentValue::NEGATIVE_OUT_OF_RANGE) {
1150 velocity.value.value = VelocityComponentValue::NEGATIVE_OUT_OF_RANGE;
1151 } else if (value > VelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1152 velocity.value.value = VelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1153 } else {
1154 velocity.value.value = static_cast<int16_t>(value);
1155 }
1156
1157 // limit confidence range
1158 if(confidence == std::numeric_limits<double>::infinity()) {
1159 velocity.confidence.value = SpeedConfidence::UNAVAILABLE;
1160 } else if (confidence > SpeedConfidence::MAX || confidence < SpeedConfidence::MIN) {
1161 velocity.confidence.value = SpeedConfidence::OUT_OF_RANGE;
1162 } else {
1163 velocity.confidence.value = static_cast<uint8_t>(confidence);
1164 }
1165}
1166
1179inline void setVelocityOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_velocity,
1180 const double x_std = std::numeric_limits<double>::infinity(),
1181 const double y_std = std::numeric_limits<double>::infinity(),
1182 const double z_std = std::numeric_limits<double>::infinity()) {
1183 object.velocity.choice = Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY;
1184 setVelocityComponent(object.velocity.cartesian_velocity.x_velocity, cartesian_velocity.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1185 setVelocityComponent(object.velocity.cartesian_velocity.y_velocity, cartesian_velocity.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1186 if (cartesian_velocity.z != 0.0) {
1187 setVelocityComponent(object.velocity.cartesian_velocity.z_velocity, cartesian_velocity.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1188 object.velocity.cartesian_velocity.z_velocity_is_present = true;
1189 }
1190 object.velocity_is_present = true;
1191}
1192
1204inline void setAccelerationComponent(AccelerationComponent& acceleration, const double value,
1205 const double confidence = std::numeric_limits<double>::infinity()) {
1206 // limit value range
1207 if (value < AccelerationValue::NEGATIVE_OUT_OF_RANGE) {
1208 acceleration.value.value = AccelerationValue::NEGATIVE_OUT_OF_RANGE;
1209 } else if (value > AccelerationValue::POSITIVE_OUT_OF_RANGE) {
1210 acceleration.value.value = AccelerationValue::POSITIVE_OUT_OF_RANGE;
1211 } else {
1212 acceleration.value.value = static_cast<int16_t>(value);
1213 }
1214
1215 // limit confidence range
1216 if(confidence == std::numeric_limits<double>::infinity()) {
1217 acceleration.confidence.value = AccelerationConfidence::UNAVAILABLE;
1218 } else if (confidence > AccelerationConfidence::MAX || confidence < AccelerationConfidence::MIN) {
1219 acceleration.confidence.value = AccelerationConfidence::OUT_OF_RANGE;
1220 } else {
1221 acceleration.confidence.value = static_cast<uint8_t>(confidence);
1222 }
1223}
1224
1237inline void setAccelerationOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_acceleration,
1238 const double x_std = std::numeric_limits<double>::infinity(),
1239 const double y_std = std::numeric_limits<double>::infinity(),
1240 const double z_std = std::numeric_limits<double>::infinity()) {
1241 object.acceleration.choice = Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION;
1242 setAccelerationComponent(object.acceleration.cartesian_acceleration.x_acceleration, cartesian_acceleration.x * 10,
1243 x_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1244 setAccelerationComponent(object.acceleration.cartesian_acceleration.y_acceleration, cartesian_acceleration.y * 10,
1245 y_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1246 if (cartesian_acceleration.z != 0.0) {
1247 setAccelerationComponent(object.acceleration.cartesian_acceleration.z_acceleration, cartesian_acceleration.z * 10,
1248 z_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1249 object.acceleration.cartesian_acceleration.z_acceleration_is_present = true;
1250 }
1251 object.acceleration_is_present = true;
1252}
1253
1264inline void setYawOfPerceivedObject(PerceivedObject& object, const double yaw,
1265 double yaw_std = std::numeric_limits<double>::infinity()) {
1266 // wrap angle to range [0, 360)
1267 double yaw_in_degrees = yaw * 180 / M_PI;
1268 while (yaw_in_degrees >= 360.0) yaw_in_degrees -= 360.0;
1269 while (yaw_in_degrees < 0.0) yaw_in_degrees += 360.0;
1270 object.angles.z_angle.value.value = yaw_in_degrees * 10;
1271
1272 if(yaw_std == std::numeric_limits<double>::infinity()) {
1273 object.angles.z_angle.confidence.value = AngleConfidence::UNAVAILABLE;
1274 } else {
1275 yaw_std *= 180.0 / M_PI;
1276 yaw_std *= 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to 0.1 degrees
1277
1278 if (yaw_std > AngleConfidence::MAX || yaw_std < AngleConfidence::MIN) {
1279 object.angles.z_angle.confidence.value = AngleConfidence::OUT_OF_RANGE;
1280 } else {
1281 object.angles.z_angle.confidence.value = static_cast<uint8_t>(yaw_std);
1282 }
1283 }
1284 object.angles_is_present = true;
1285}
1286
1298inline void setYawRateOfPerceivedObject(PerceivedObject& object, const double yaw_rate,
1299 double yaw_rate_std = std::numeric_limits<double>::infinity()) {
1300 double yaw_rate_in_degrees = yaw_rate * 180.0 / M_PI;
1301 // limit value range
1302 if (yaw_rate_in_degrees < CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE) {
1303 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE;
1304 } else if (yaw_rate_in_degrees > CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1305 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1306 }
1307
1308 object.z_angular_velocity.value.value = yaw_rate_in_degrees;
1309
1310 if(yaw_rate_std == std::numeric_limits<double>::infinity()) {
1311 object.z_angular_velocity.confidence.value = AngularSpeedConfidence::UNAVAILABLE;
1312 } else {
1313 yaw_rate_std *= 180.0 / M_PI;
1314 yaw_rate_std *= etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to degrees/s
1315 // How stupid is this?!
1316 static const std::map<double, uint8_t> confidence_map = {
1317 {1.0, AngularSpeedConfidence::DEG_SEC_01},
1318 {2.0, AngularSpeedConfidence::DEG_SEC_02},
1319 {5.0, AngularSpeedConfidence::DEG_SEC_05},
1320 {10.0, AngularSpeedConfidence::DEG_SEC_10},
1321 {20.0, AngularSpeedConfidence::DEG_SEC_20},
1322 {50.0, AngularSpeedConfidence::DEG_SEC_50},
1323 {std::numeric_limits<double>::infinity(), AngularSpeedConfidence::OUT_OF_RANGE},
1324 };
1325 for(const auto& [thresh, conf_val] : confidence_map) {
1326 if (yaw_rate_std <= thresh) {
1327 object.z_angular_velocity.confidence.value = conf_val;
1328 break;
1329 }
1330 }
1331 }
1332
1333 object.z_angular_velocity_is_present = true;
1334}
1335
1350inline void setObjectDimension(ObjectDimension& dimension, const double value,
1351 const double confidence = std::numeric_limits<double>::infinity()) {
1352 // limit value range
1353 if (value < ObjectDimensionValue::MIN || value > ObjectDimensionValue::MAX) {
1354 dimension.value.value = ObjectDimensionValue::OUT_OF_RANGE;
1355 } else {
1356 dimension.value.value = static_cast<uint16_t>(value);
1357 }
1358
1359 // limit confidence range
1360 if (confidence == std::numeric_limits<double>::infinity()) {
1361 dimension.confidence.value = ObjectDimensionConfidence::UNAVAILABLE;
1362 } else if (confidence > ObjectDimensionConfidence::MAX || confidence < ObjectDimensionConfidence::MIN) {
1363 dimension.confidence.value = ObjectDimensionConfidence::OUT_OF_RANGE;
1364 } else {
1365 dimension.confidence.value = static_cast<uint8_t>(confidence);
1366 }
1367
1368}
1369
1380inline void setXDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1381 const double std = std::numeric_limits<double>::infinity()) {
1382 setObjectDimension(object.object_dimension_x, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1383 object.object_dimension_x_is_present = true;
1384}
1385
1396inline void setYDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1397 const double std = std::numeric_limits<double>::infinity()) {
1398 setObjectDimension(object.object_dimension_y, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1399 object.object_dimension_y_is_present = true;
1400}
1401
1412inline void setZDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1413 const double std = std::numeric_limits<double>::infinity()) {
1414 setObjectDimension(object.object_dimension_z, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1415 object.object_dimension_z_is_present = true;
1416}
1417
1429inline void setDimensionsOfPerceivedObject(PerceivedObject& object, const gm::Vector3& dimensions,
1430 const double x_std = std::numeric_limits<double>::infinity(),
1431 const double y_std = std::numeric_limits<double>::infinity(),
1432 const double z_std = std::numeric_limits<double>::infinity()) {
1433 setXDimensionOfPerceivedObject(object, dimensions.x, x_std);
1434 setYDimensionOfPerceivedObject(object, dimensions.y, y_std);
1435 setZDimensionOfPerceivedObject(object, dimensions.z, z_std);
1436}
1437
1447inline void initPerceivedObject(PerceivedObject& object, const gm::Point& point, const int16_t delta_time = 0) {
1448 setPositionOfPerceivedObject(object, point);
1449 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1450}
1451
1464inline void initPerceivedObjectWithUTMPosition(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1465 const gm::PointStamped& point, const int16_t delta_time = 0) {
1466 setUTMPositionOfPerceivedObject(cpm, object, point);
1467 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1468}
1469
1479inline void initPerceivedObjectContainer(WrappedCpmContainer& container, const uint8_t n_objects = 0) {
1480 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER;
1481 container.container_data_perceived_object_container.number_of_perceived_objects.value = n_objects;
1482}
1483
1497inline void addPerceivedObjectToContainer(WrappedCpmContainer& container, const PerceivedObject& perceived_object) {
1498 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER) {
1499 container.container_data_perceived_object_container.perceived_objects.array.push_back(perceived_object);
1500 container.container_data_perceived_object_container.number_of_perceived_objects.value =
1501 container.container_data_perceived_object_container.perceived_objects.array.size();
1502 } else {
1503 throw std::invalid_argument("Container is not a PerceivedObjectContainer");
1504 }
1505}
1506
1519inline void addContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1520 // check for maximum number of containers
1521 if (cpm.payload.cpm_containers.value.array.size() < WrappedCpmContainers::MAX_SIZE) {
1522 cpm.payload.cpm_containers.value.array.push_back(container);
1523 } else {
1524 throw std::invalid_argument("Maximum number of CPM-Containers reached");
1525 }
1526}
1527
1536inline void setWGSRefPosConfidence(CollectivePerceptionMessage& cpm, const std::array<double, 4>& covariance_matrix) {
1537 setWGSPosConfidenceEllipse(cpm.payload.management_container.reference_position.position_confidence_ellipse,
1538 covariance_matrix);
1539}
1540
1549inline void initSensorInformationContainer(WrappedCpmContainer& container) {
1550 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER;
1551 container.container_data_sensor_information_container.array = std::vector<SensorInformation>();
1552}
1553
1564inline void setSensorID(SensorInformation& sensor_information, const uint8_t sensor_id = 0) {
1565 throwIfOutOfRange(sensor_id, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1566 sensor_information.sensor_id.value = sensor_id;
1567}
1568
1579inline void setSensorType(SensorInformation& sensor_information, const uint8_t sensor_type = SensorType::UNDEFINED) {
1580 throwIfOutOfRange(sensor_type, SensorType::MIN, SensorType::MAX, "SensorType");
1581 sensor_information.sensor_type.value = sensor_type;
1582}
1583
1602inline void addSensorInformationToContainer(WrappedCpmContainer& container, const SensorInformation& sensor_information) {
1603 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1604 // check for maximum number of SensorInformation entries
1605 if (container.container_data_sensor_information_container.array.size() < SensorInformationContainer::MAX_SIZE ) {
1606 throwIfOutOfRange(sensor_information.sensor_id.value, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1607 throwIfOutOfRange(sensor_information.sensor_type.value, SensorType::MIN, SensorType::MAX, "SensorType");
1608 container.container_data_sensor_information_container.array.push_back(sensor_information);
1609 } else {
1610 throw std::invalid_argument("Maximum number of entries SensorInformationContainers reached");
1611 }
1612 } else {
1613 throw std::invalid_argument("Container is not a SensorInformationContainer");
1614 }
1615}
1616
1631inline void addSensorInformationContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1632 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1633 throwIfOutOfRange(container.container_data_sensor_information_container.array.size(),
1634 SensorInformationContainer::MIN_SIZE, SensorInformationContainer::MAX_SIZE, "SensorInformationContainer array size"
1635 );
1636 addContainerToCPM(cpm, container);
1637 } else {
1638 throw std::invalid_argument("Container is not a SensorInformationContainer");
1639 }
1640}
1641
1642} // namespace etsi_its_cpm_ts_msgs::access

◆ addSensorInformationToContainer()

void etsi_its_cpm_ts_msgs::access::addSensorInformationToContainer ( WrappedCpmContainer & container,
const SensorInformation & sensor_information )
inline

Adds a SensorInformation to the SensorInformationContainer / WrappedCpmContainer.

This function checks if the provided container is a SensorInformationContainer. If it is, the function adds the given SensorInformation to the container's sensor_information array. If the container is not a SensorInformationContainer, the function throws an std::invalid_argument exception. If the maximum number of SensorInformation entries is reached, it throws an exception. If the sensor_id or sensor_type is out of range, it throws an exception.

Parameters
containerThe WrappedCpmContainer to which the SensorInformation will be added.
sensor_informationThe SensorInformation to add to the container.
Exceptions
std::invalid_argumentif the container is not a SensorInformationContainer.
std::invalid_argumentif the maximum number of SensorInformation entries is reached.
std::invalid_argumentif the sensor_id or sensor_type is out of range.

Definition at line 873 of file cpm_ts_setters.h.

909 {
910
912
922inline void setItsPduHeader(CollectivePerceptionMessage& cpm, const uint32_t station_id,
923 const uint8_t protocol_version = 0) {
924 setItsPduHeader(cpm.header, MessageId::CPM, station_id, protocol_version);
925}
926
938inline void setReferenceTime(
939 CollectivePerceptionMessage& cpm, const uint64_t unix_nanosecs,
940 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
941 TimestampIts t_its;
942 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
943 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
944 cpm.payload.management_container.reference_time = t_its;
945}
946
958inline void setReferencePosition(CollectivePerceptionMessage& cpm, const double latitude, const double longitude,
959 const double altitude = AltitudeValue::UNAVAILABLE) {
960 setReferencePosition(cpm.payload.management_container.reference_position, latitude, longitude, altitude);
961}
962
975inline void setFromUTMPosition(CollectivePerceptionMessage& cpm, const gm::PointStamped& utm_position, const int& zone,
976 const bool& northp) {
977 setFromUTMPosition(cpm.payload.management_container.reference_position, utm_position, zone, northp);
978}
979
988inline void setIdOfPerceivedObject(PerceivedObject& object, const uint16_t id) {
989 object.object_id.value = id;
990 object.object_id_is_present = true;
991}
992
1004inline void setMeasurementDeltaTimeOfPerceivedObject(PerceivedObject& object, const int16_t delta_time = 0) {
1005 if (delta_time < DeltaTimeMilliSecondSigned::MIN || delta_time > DeltaTimeMilliSecondSigned::MAX) {
1006 throw std::invalid_argument("MeasurementDeltaTime out of range");
1007 } else {
1008 object.measurement_delta_time.value = delta_time;
1009 }
1010}
1011
1025inline void setCartesianCoordinateWithConfidence(CartesianCoordinateWithConfidence& coordinate, const double value,
1026 const double confidence = std::numeric_limits<double>::infinity()) {
1027 // limit value range
1028 if (value < CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE) {
1029 coordinate.value.value = CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE;
1030 } else if (value > CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE) {
1031 coordinate.value.value = CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE;
1032 } else {
1033 coordinate.value.value = static_cast<int32_t>(value);
1034 }
1035
1036 // limit confidence range
1037 if (confidence == std::numeric_limits<double>::infinity()) {
1038 coordinate.confidence.value = CoordinateConfidence::UNAVAILABLE;
1039 } else if (confidence > CoordinateConfidence::MAX || confidence < CoordinateConfidence::MIN) {
1040 coordinate.confidence.value = CoordinateConfidence::OUT_OF_RANGE;
1041 } else {
1042 coordinate.confidence.value = static_cast<uint16_t>(confidence);
1043 }
1044}
1045
1057inline void setPositionOfPerceivedObject(PerceivedObject& object, const gm::Point& point,
1058 const double x_std = std::numeric_limits<double>::infinity(),
1059 const double y_std = std::numeric_limits<double>::infinity(),
1060 const double z_std = std::numeric_limits<double>::infinity()) {
1061 setCartesianCoordinateWithConfidence(object.position.x_coordinate, point.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1062 setCartesianCoordinateWithConfidence(object.position.y_coordinate, point.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1063 if (point.z != 0.0) {
1064 setCartesianCoordinateWithConfidence(object.position.z_coordinate, point.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1065 object.position.z_coordinate_is_present = true;
1066 }
1067}
1068
1084inline void setUTMPositionOfPerceivedObject(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1085 const gm::PointStamped& utm_position,
1086 const double x_std = std::numeric_limits<double>::infinity(),
1087 const double y_std = std::numeric_limits<double>::infinity(),
1088 const double z_std = std::numeric_limits<double>::infinity()) {
1089 gm::PointStamped reference_position = getUTMPosition(cpm);
1090 if (utm_position.header.frame_id != reference_position.header.frame_id) {
1091 throw std::invalid_argument("UTM-Position frame_id (" + utm_position.header.frame_id +
1092 ") does not match the reference position frame_id (" + reference_position.header.frame_id +
1093 ")");
1094 }
1095 setCartesianCoordinateWithConfidence(object.position.x_coordinate,
1096 (utm_position.point.x - reference_position.point.x) * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1097 setCartesianCoordinateWithConfidence(object.position.y_coordinate,
1098 (utm_position.point.y - reference_position.point.y) * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1099 if (utm_position.point.z != 0.0) {
1100 setCartesianCoordinateWithConfidence(object.position.z_coordinate,
1101 (utm_position.point.z - reference_position.point.z) * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1102 object.position.z_coordinate_is_present = true;
1103 }
1104}
1105
1117inline void setVelocityComponent(VelocityComponent& velocity, const double value,
1118 const double confidence = std::numeric_limits<double>::infinity()) {
1119 // limit value range
1120 if (value < VelocityComponentValue::NEGATIVE_OUT_OF_RANGE) {
1121 velocity.value.value = VelocityComponentValue::NEGATIVE_OUT_OF_RANGE;
1122 } else if (value > VelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1123 velocity.value.value = VelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1124 } else {
1125 velocity.value.value = static_cast<int16_t>(value);
1126 }
1127
1128 // limit confidence range
1129 if(confidence == std::numeric_limits<double>::infinity()) {
1130 velocity.confidence.value = SpeedConfidence::UNAVAILABLE;
1131 } else if (confidence > SpeedConfidence::MAX || confidence < SpeedConfidence::MIN) {
1132 velocity.confidence.value = SpeedConfidence::OUT_OF_RANGE;
1133 } else {
1134 velocity.confidence.value = static_cast<uint8_t>(confidence);
1135 }
1136}
1137
1150inline void setVelocityOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_velocity,
1151 const double x_std = std::numeric_limits<double>::infinity(),
1152 const double y_std = std::numeric_limits<double>::infinity(),
1153 const double z_std = std::numeric_limits<double>::infinity()) {
1154 object.velocity.choice = Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY;
1155 setVelocityComponent(object.velocity.cartesian_velocity.x_velocity, cartesian_velocity.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1156 setVelocityComponent(object.velocity.cartesian_velocity.y_velocity, cartesian_velocity.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1157 if (cartesian_velocity.z != 0.0) {
1158 setVelocityComponent(object.velocity.cartesian_velocity.z_velocity, cartesian_velocity.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1159 object.velocity.cartesian_velocity.z_velocity_is_present = true;
1160 }
1161 object.velocity_is_present = true;
1162}
1163
1175inline void setAccelerationComponent(AccelerationComponent& acceleration, const double value,
1176 const double confidence = std::numeric_limits<double>::infinity()) {
1177 // limit value range
1178 if (value < AccelerationValue::NEGATIVE_OUT_OF_RANGE) {
1179 acceleration.value.value = AccelerationValue::NEGATIVE_OUT_OF_RANGE;
1180 } else if (value > AccelerationValue::POSITIVE_OUT_OF_RANGE) {
1181 acceleration.value.value = AccelerationValue::POSITIVE_OUT_OF_RANGE;
1182 } else {
1183 acceleration.value.value = static_cast<int16_t>(value);
1184 }
1185
1186 // limit confidence range
1187 if(confidence == std::numeric_limits<double>::infinity()) {
1188 acceleration.confidence.value = AccelerationConfidence::UNAVAILABLE;
1189 } else if (confidence > AccelerationConfidence::MAX || confidence < AccelerationConfidence::MIN) {
1190 acceleration.confidence.value = AccelerationConfidence::OUT_OF_RANGE;
1191 } else {
1192 acceleration.confidence.value = static_cast<uint8_t>(confidence);
1193 }
1194}
1195
1208inline void setAccelerationOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_acceleration,
1209 const double x_std = std::numeric_limits<double>::infinity(),
1210 const double y_std = std::numeric_limits<double>::infinity(),
1211 const double z_std = std::numeric_limits<double>::infinity()) {
1212 object.acceleration.choice = Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION;
1213 setAccelerationComponent(object.acceleration.cartesian_acceleration.x_acceleration, cartesian_acceleration.x * 10,
1214 x_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1215 setAccelerationComponent(object.acceleration.cartesian_acceleration.y_acceleration, cartesian_acceleration.y * 10,
1216 y_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1217 if (cartesian_acceleration.z != 0.0) {
1218 setAccelerationComponent(object.acceleration.cartesian_acceleration.z_acceleration, cartesian_acceleration.z * 10,
1219 z_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1220 object.acceleration.cartesian_acceleration.z_acceleration_is_present = true;
1221 }
1222 object.acceleration_is_present = true;
1223}
1224
1235inline void setYawOfPerceivedObject(PerceivedObject& object, const double yaw,
1236 double yaw_std = std::numeric_limits<double>::infinity()) {
1237 // wrap angle to range [0, 360)
1238 double yaw_in_degrees = yaw * 180 / M_PI;
1239 while (yaw_in_degrees >= 360.0) yaw_in_degrees -= 360.0;
1240 while (yaw_in_degrees < 0.0) yaw_in_degrees += 360.0;
1241 object.angles.z_angle.value.value = yaw_in_degrees * 10;
1242
1243 if(yaw_std == std::numeric_limits<double>::infinity()) {
1244 object.angles.z_angle.confidence.value = AngleConfidence::UNAVAILABLE;
1245 } else {
1246 yaw_std *= 180.0 / M_PI;
1247 yaw_std *= 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to 0.1 degrees
1248
1249 if (yaw_std > AngleConfidence::MAX || yaw_std < AngleConfidence::MIN) {
1250 object.angles.z_angle.confidence.value = AngleConfidence::OUT_OF_RANGE;
1251 } else {
1252 object.angles.z_angle.confidence.value = static_cast<uint8_t>(yaw_std);
1253 }
1254 }
1255 object.angles_is_present = true;
1256}
1257
1269inline void setYawRateOfPerceivedObject(PerceivedObject& object, const double yaw_rate,
1270 double yaw_rate_std = std::numeric_limits<double>::infinity()) {
1271 double yaw_rate_in_degrees = yaw_rate * 180.0 / M_PI;
1272 // limit value range
1273 if (yaw_rate_in_degrees < CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE) {
1274 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE;
1275 } else if (yaw_rate_in_degrees > CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1276 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1277 }
1278
1279 object.z_angular_velocity.value.value = yaw_rate_in_degrees;
1280
1281 if(yaw_rate_std == std::numeric_limits<double>::infinity()) {
1282 object.z_angular_velocity.confidence.value = AngularSpeedConfidence::UNAVAILABLE;
1283 } else {
1284 yaw_rate_std *= 180.0 / M_PI;
1285 yaw_rate_std *= etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to degrees/s
1286 // How stupid is this?!
1287 static const std::map<double, uint8_t> confidence_map = {
1288 {1.0, AngularSpeedConfidence::DEG_SEC_01},
1289 {2.0, AngularSpeedConfidence::DEG_SEC_02},
1290 {5.0, AngularSpeedConfidence::DEG_SEC_05},
1291 {10.0, AngularSpeedConfidence::DEG_SEC_10},
1292 {20.0, AngularSpeedConfidence::DEG_SEC_20},
1293 {50.0, AngularSpeedConfidence::DEG_SEC_50},
1294 {std::numeric_limits<double>::infinity(), AngularSpeedConfidence::OUT_OF_RANGE},
1295 };
1296 for(const auto& [thresh, conf_val] : confidence_map) {
1297 if (yaw_rate_std <= thresh) {
1298 object.z_angular_velocity.confidence.value = conf_val;
1299 break;
1300 }
1301 }
1302 }
1303
1304 object.z_angular_velocity_is_present = true;
1305}
1306
1321inline void setObjectDimension(ObjectDimension& dimension, const double value,
1322 const double confidence = std::numeric_limits<double>::infinity()) {
1323 // limit value range
1324 if (value < ObjectDimensionValue::MIN || value > ObjectDimensionValue::MAX) {
1325 dimension.value.value = ObjectDimensionValue::OUT_OF_RANGE;
1326 } else {
1327 dimension.value.value = static_cast<uint16_t>(value);
1328 }
1329
1330 // limit confidence range
1331 if (confidence == std::numeric_limits<double>::infinity()) {
1332 dimension.confidence.value = ObjectDimensionConfidence::UNAVAILABLE;
1333 } else if (confidence > ObjectDimensionConfidence::MAX || confidence < ObjectDimensionConfidence::MIN) {
1334 dimension.confidence.value = ObjectDimensionConfidence::OUT_OF_RANGE;
1335 } else {
1336 dimension.confidence.value = static_cast<uint8_t>(confidence);
1337 }
1338
1339}
1340
1351inline void setXDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1352 const double std = std::numeric_limits<double>::infinity()) {
1353 setObjectDimension(object.object_dimension_x, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1354 object.object_dimension_x_is_present = true;
1355}
1356
1367inline void setYDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1368 const double std = std::numeric_limits<double>::infinity()) {
1369 setObjectDimension(object.object_dimension_y, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1370 object.object_dimension_y_is_present = true;
1371}
1372
1383inline void setZDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1384 const double std = std::numeric_limits<double>::infinity()) {
1385 setObjectDimension(object.object_dimension_z, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1386 object.object_dimension_z_is_present = true;
1387}
1388
1400inline void setDimensionsOfPerceivedObject(PerceivedObject& object, const gm::Vector3& dimensions,
1401 const double x_std = std::numeric_limits<double>::infinity(),
1402 const double y_std = std::numeric_limits<double>::infinity(),
1403 const double z_std = std::numeric_limits<double>::infinity()) {
1404 setXDimensionOfPerceivedObject(object, dimensions.x, x_std);
1405 setYDimensionOfPerceivedObject(object, dimensions.y, y_std);
1406 setZDimensionOfPerceivedObject(object, dimensions.z, z_std);
1407}
1408
1418inline void initPerceivedObject(PerceivedObject& object, const gm::Point& point, const int16_t delta_time = 0) {
1419 setPositionOfPerceivedObject(object, point);
1420 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1421}
1422
1435inline void initPerceivedObjectWithUTMPosition(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1436 const gm::PointStamped& point, const int16_t delta_time = 0) {
1437 setUTMPositionOfPerceivedObject(cpm, object, point);
1438 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1439}
1440
1450inline void initPerceivedObjectContainer(WrappedCpmContainer& container, const uint8_t n_objects = 0) {
1451 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER;
1452 container.container_data_perceived_object_container.number_of_perceived_objects.value = n_objects;
1453}
1454
1468inline void addPerceivedObjectToContainer(WrappedCpmContainer& container, const PerceivedObject& perceived_object) {
1469 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER) {
1470 container.container_data_perceived_object_container.perceived_objects.array.push_back(perceived_object);
1471 container.container_data_perceived_object_container.number_of_perceived_objects.value =
1472 container.container_data_perceived_object_container.perceived_objects.array.size();
1473 } else {
1474 throw std::invalid_argument("Container is not a PerceivedObjectContainer");
1475 }
1476}
1477
1490inline void addContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1491 // check for maximum number of containers
1492 if (cpm.payload.cpm_containers.value.array.size() < WrappedCpmContainers::MAX_SIZE) {
1493 cpm.payload.cpm_containers.value.array.push_back(container);
1494 } else {
1495 throw std::invalid_argument("Maximum number of CPM-Containers reached");
1496 }
1497}
1498
1507inline void setWGSRefPosConfidence(CollectivePerceptionMessage& cpm, const std::array<double, 4>& covariance_matrix) {
1508 setWGSPosConfidenceEllipse(cpm.payload.management_container.reference_position.position_confidence_ellipse,
1509 covariance_matrix);
1510}
1511
1520inline void initSensorInformationContainer(WrappedCpmContainer& container) {
1521 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER;
1522 container.container_data_sensor_information_container.array = std::vector<SensorInformation>();
1523}
1524
1535inline void setSensorID(SensorInformation& sensor_information, const uint8_t sensor_id = 0) {
1536 throwIfOutOfRange(sensor_id, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1537 sensor_information.sensor_id.value = sensor_id;
1538}
1539
1550inline void setSensorType(SensorInformation& sensor_information, const uint8_t sensor_type = SensorType::UNDEFINED) {
1551 throwIfOutOfRange(sensor_type, SensorType::MIN, SensorType::MAX, "SensorType");
1552 sensor_information.sensor_type.value = sensor_type;
1553}
1554
1573inline void addSensorInformationToContainer(WrappedCpmContainer& container, const SensorInformation& sensor_information) {
1574 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1575 // check for maximum number of SensorInformation entries
1576 if (container.container_data_sensor_information_container.array.size() < SensorInformationContainer::MAX_SIZE ) {
1577 throwIfOutOfRange(sensor_information.sensor_id.value, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1578 throwIfOutOfRange(sensor_information.sensor_type.value, SensorType::MIN, SensorType::MAX, "SensorType");
1579 container.container_data_sensor_information_container.array.push_back(sensor_information);
1580 } else {
1581 throw std::invalid_argument("Maximum number of entries SensorInformationContainers reached");
1582 }
1583 } else {
1584 throw std::invalid_argument("Container is not a SensorInformationContainer");
1585 }
1586}
1587
1602inline void addSensorInformationContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1603 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1604 throwIfOutOfRange(container.container_data_sensor_information_container.array.size(),
1605 SensorInformationContainer::MIN_SIZE, SensorInformationContainer::MAX_SIZE, "SensorInformationContainer array size"
1606 );
1607 addContainerToCPM(cpm, container);
1608 } else {
1609 throw std::invalid_argument("Container is not a SensorInformationContainer");
1610 }
1611}
1612
1613} // namespace etsi_its_cpm_ts_msgs::access

◆ confidenceEllipseFromCovMatrix()

std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::confidenceEllipseFromCovMatrix ( const std::array< double, 4 > & covariance_matrix,
const double object_heading )
inline

Gets the values needed to set a confidence ellipse from a covariance matrix.

Parameters
covariance_matrixThe four values of the covariance matrix in the order: cov_xx, cov_xy, cov_yx, cov_yy The matrix has to be SPD, otherwise a std::invalid_argument exception is thrown. Its coordinate system is aligned with the object (x = longitudinal, y = lateral)
object_headingThe heading of the object in rad, with respect to WGS84
Returns
std::tuple<double, double, double> semi_major_axis [m], semi_minor_axis [m], orientation [deg], with respect to WGS84

Definition at line 376 of file cpm_ts_setters.h.

377 {
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
397inline 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

◆ confidenceEllipseFromWGSCovMatrix()

std::tuple< double, double, double > etsi_its_cpm_ts_msgs::access::confidenceEllipseFromWGSCovMatrix ( const std::array< double, 4 > & covariance_matrix)
inline

Gets the values needed to set a confidence ellipse from a covariance matrix.

Parameters
covariance_matrixThe four values of the covariance matrix in the order: cov_xx, cov_xy, cov_yx, cov_yy The matrix has to be SPD, otherwise a std::invalid_argument exception is thrown. Its coordinate system is aligned with the WGS axes (x = North, y = East)
object_headingThe heading of the object in rad, with respect to WGS84
Returns
std::tuple<double, double, double> semi_major_axis [m], semi_minor_axis [m], orientation [deg], with respect to WGS84

Definition at line 417 of file cpm_ts_setters.h.

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},

◆ getLeapSecondInsertionsSince2004()

uint16_t etsi_its_cpm_ts_msgs::access::etsi_its_msgs::getLeapSecondInsertionsSince2004 ( const uint64_t unix_seconds)
inline

Get the leap second insertions since 2004 for given unix seconds.

Parameters
unix_secondsthe current unix seconds for that the leap second insertions since 2004 shall be provided
Returns
uint16_t the number of leap second insertions since 2004 for unix_seconds

Definition at line 61 of file cpm_ts_setters.h.

68 {
69 TimestampIts t_its;

◆ initPerceivedObject()

void etsi_its_cpm_ts_msgs::access::initPerceivedObject ( PerceivedObject & object,
const gm::Point & point,
const int16_t delta_time = 0 )
inline

Initializes a PerceivedObject with the given point and delta time.

This function sets the position and measurement delta time of the PerceivedObject.

Parameters
objectThe PerceivedObject to be initialized.
pointThe position of the PerceivedObject relative to the CPM's reference position in meters.
delta_timeThe measurement delta time of the PerceivedObject in milliseconds (default = 0).

Definition at line 718 of file cpm_ts_setters.h.

◆ initPerceivedObjectContainer()

void etsi_its_cpm_ts_msgs::access::initPerceivedObjectContainer ( WrappedCpmContainer & container,
const uint8_t n_objects = 0 )
inline

Initializes a WrappedCpmContainer as a PerceivedObjectContainer with the given number of objects.

This function sets the container ID to CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER and initializes the number of perceived objects in the container to the specified value.

Parameters
containerA reference to the WrappedCpmContainer to be initialized as a PerceivedObjectContainer.
n_objectsThe number of perceived objects to initialize in the container. Default is 0.

Definition at line 750 of file cpm_ts_setters.h.

786 {
787
789
799inline void setItsPduHeader(CollectivePerceptionMessage& cpm, const uint32_t station_id,
800 const uint8_t protocol_version = 0) {
801 setItsPduHeader(cpm.header, MessageId::CPM, station_id, protocol_version);
802}
803
815inline void setReferenceTime(
816 CollectivePerceptionMessage& cpm, const uint64_t unix_nanosecs,
817 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
818 TimestampIts t_its;
819 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
820 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
821 cpm.payload.management_container.reference_time = t_its;
822}
823
835inline void setReferencePosition(CollectivePerceptionMessage& cpm, const double latitude, const double longitude,
836 const double altitude = AltitudeValue::UNAVAILABLE) {
837 setReferencePosition(cpm.payload.management_container.reference_position, latitude, longitude, altitude);
838}
839
852inline void setFromUTMPosition(CollectivePerceptionMessage& cpm, const gm::PointStamped& utm_position, const int& zone,
853 const bool& northp) {
854 setFromUTMPosition(cpm.payload.management_container.reference_position, utm_position, zone, northp);
855}
856
865inline void setIdOfPerceivedObject(PerceivedObject& object, const uint16_t id) {
866 object.object_id.value = id;
867 object.object_id_is_present = true;
868}
869
881inline void setMeasurementDeltaTimeOfPerceivedObject(PerceivedObject& object, const int16_t delta_time = 0) {
882 if (delta_time < DeltaTimeMilliSecondSigned::MIN || delta_time > DeltaTimeMilliSecondSigned::MAX) {
883 throw std::invalid_argument("MeasurementDeltaTime out of range");
884 } else {
885 object.measurement_delta_time.value = delta_time;
886 }
887}
888
902inline void setCartesianCoordinateWithConfidence(CartesianCoordinateWithConfidence& coordinate, const double value,
903 const double confidence = std::numeric_limits<double>::infinity()) {
904 // limit value range
905 if (value < CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE) {
906 coordinate.value.value = CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE;
907 } else if (value > CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE) {
908 coordinate.value.value = CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE;
909 } else {
910 coordinate.value.value = static_cast<int32_t>(value);
911 }
912
913 // limit confidence range
914 if (confidence == std::numeric_limits<double>::infinity()) {
915 coordinate.confidence.value = CoordinateConfidence::UNAVAILABLE;
916 } else if (confidence > CoordinateConfidence::MAX || confidence < CoordinateConfidence::MIN) {
917 coordinate.confidence.value = CoordinateConfidence::OUT_OF_RANGE;
918 } else {
919 coordinate.confidence.value = static_cast<uint16_t>(confidence);
920 }
921}
922
934inline void setPositionOfPerceivedObject(PerceivedObject& object, const gm::Point& point,
935 const double x_std = std::numeric_limits<double>::infinity(),
936 const double y_std = std::numeric_limits<double>::infinity(),
937 const double z_std = std::numeric_limits<double>::infinity()) {
938 setCartesianCoordinateWithConfidence(object.position.x_coordinate, point.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
939 setCartesianCoordinateWithConfidence(object.position.y_coordinate, point.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
940 if (point.z != 0.0) {
941 setCartesianCoordinateWithConfidence(object.position.z_coordinate, point.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
942 object.position.z_coordinate_is_present = true;
943 }
944}
945
961inline void setUTMPositionOfPerceivedObject(CollectivePerceptionMessage& cpm, PerceivedObject& object,
962 const gm::PointStamped& utm_position,
963 const double x_std = std::numeric_limits<double>::infinity(),
964 const double y_std = std::numeric_limits<double>::infinity(),
965 const double z_std = std::numeric_limits<double>::infinity()) {
966 gm::PointStamped reference_position = getUTMPosition(cpm);
967 if (utm_position.header.frame_id != reference_position.header.frame_id) {
968 throw std::invalid_argument("UTM-Position frame_id (" + utm_position.header.frame_id +
969 ") does not match the reference position frame_id (" + reference_position.header.frame_id +
970 ")");
971 }
972 setCartesianCoordinateWithConfidence(object.position.x_coordinate,
973 (utm_position.point.x - reference_position.point.x) * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
974 setCartesianCoordinateWithConfidence(object.position.y_coordinate,
975 (utm_position.point.y - reference_position.point.y) * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
976 if (utm_position.point.z != 0.0) {
977 setCartesianCoordinateWithConfidence(object.position.z_coordinate,
978 (utm_position.point.z - reference_position.point.z) * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
979 object.position.z_coordinate_is_present = true;
980 }
981}
982
994inline void setVelocityComponent(VelocityComponent& velocity, const double value,
995 const double confidence = std::numeric_limits<double>::infinity()) {
996 // limit value range
997 if (value < VelocityComponentValue::NEGATIVE_OUT_OF_RANGE) {
998 velocity.value.value = VelocityComponentValue::NEGATIVE_OUT_OF_RANGE;
999 } else if (value > VelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1000 velocity.value.value = VelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1001 } else {
1002 velocity.value.value = static_cast<int16_t>(value);
1003 }
1004
1005 // limit confidence range
1006 if(confidence == std::numeric_limits<double>::infinity()) {
1007 velocity.confidence.value = SpeedConfidence::UNAVAILABLE;
1008 } else if (confidence > SpeedConfidence::MAX || confidence < SpeedConfidence::MIN) {
1009 velocity.confidence.value = SpeedConfidence::OUT_OF_RANGE;
1010 } else {
1011 velocity.confidence.value = static_cast<uint8_t>(confidence);
1012 }
1013}
1014
1027inline void setVelocityOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_velocity,
1028 const double x_std = std::numeric_limits<double>::infinity(),
1029 const double y_std = std::numeric_limits<double>::infinity(),
1030 const double z_std = std::numeric_limits<double>::infinity()) {
1031 object.velocity.choice = Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY;
1032 setVelocityComponent(object.velocity.cartesian_velocity.x_velocity, cartesian_velocity.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1033 setVelocityComponent(object.velocity.cartesian_velocity.y_velocity, cartesian_velocity.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1034 if (cartesian_velocity.z != 0.0) {
1035 setVelocityComponent(object.velocity.cartesian_velocity.z_velocity, cartesian_velocity.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1036 object.velocity.cartesian_velocity.z_velocity_is_present = true;
1037 }
1038 object.velocity_is_present = true;
1039}
1040
1052inline void setAccelerationComponent(AccelerationComponent& acceleration, const double value,
1053 const double confidence = std::numeric_limits<double>::infinity()) {
1054 // limit value range
1055 if (value < AccelerationValue::NEGATIVE_OUT_OF_RANGE) {
1056 acceleration.value.value = AccelerationValue::NEGATIVE_OUT_OF_RANGE;
1057 } else if (value > AccelerationValue::POSITIVE_OUT_OF_RANGE) {
1058 acceleration.value.value = AccelerationValue::POSITIVE_OUT_OF_RANGE;
1059 } else {
1060 acceleration.value.value = static_cast<int16_t>(value);
1061 }
1062
1063 // limit confidence range
1064 if(confidence == std::numeric_limits<double>::infinity()) {
1065 acceleration.confidence.value = AccelerationConfidence::UNAVAILABLE;
1066 } else if (confidence > AccelerationConfidence::MAX || confidence < AccelerationConfidence::MIN) {
1067 acceleration.confidence.value = AccelerationConfidence::OUT_OF_RANGE;
1068 } else {
1069 acceleration.confidence.value = static_cast<uint8_t>(confidence);
1070 }
1071}
1072
1085inline void setAccelerationOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_acceleration,
1086 const double x_std = std::numeric_limits<double>::infinity(),
1087 const double y_std = std::numeric_limits<double>::infinity(),
1088 const double z_std = std::numeric_limits<double>::infinity()) {
1089 object.acceleration.choice = Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION;
1090 setAccelerationComponent(object.acceleration.cartesian_acceleration.x_acceleration, cartesian_acceleration.x * 10,
1091 x_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1092 setAccelerationComponent(object.acceleration.cartesian_acceleration.y_acceleration, cartesian_acceleration.y * 10,
1093 y_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1094 if (cartesian_acceleration.z != 0.0) {
1095 setAccelerationComponent(object.acceleration.cartesian_acceleration.z_acceleration, cartesian_acceleration.z * 10,
1096 z_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1097 object.acceleration.cartesian_acceleration.z_acceleration_is_present = true;
1098 }
1099 object.acceleration_is_present = true;
1100}
1101
1112inline void setYawOfPerceivedObject(PerceivedObject& object, const double yaw,
1113 double yaw_std = std::numeric_limits<double>::infinity()) {
1114 // wrap angle to range [0, 360)
1115 double yaw_in_degrees = yaw * 180 / M_PI;
1116 while (yaw_in_degrees >= 360.0) yaw_in_degrees -= 360.0;
1117 while (yaw_in_degrees < 0.0) yaw_in_degrees += 360.0;
1118 object.angles.z_angle.value.value = yaw_in_degrees * 10;
1119
1120 if(yaw_std == std::numeric_limits<double>::infinity()) {
1121 object.angles.z_angle.confidence.value = AngleConfidence::UNAVAILABLE;
1122 } else {
1123 yaw_std *= 180.0 / M_PI;
1124 yaw_std *= 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to 0.1 degrees
1125
1126 if (yaw_std > AngleConfidence::MAX || yaw_std < AngleConfidence::MIN) {
1127 object.angles.z_angle.confidence.value = AngleConfidence::OUT_OF_RANGE;
1128 } else {
1129 object.angles.z_angle.confidence.value = static_cast<uint8_t>(yaw_std);
1130 }
1131 }
1132 object.angles_is_present = true;
1133}
1134
1146inline void setYawRateOfPerceivedObject(PerceivedObject& object, const double yaw_rate,
1147 double yaw_rate_std = std::numeric_limits<double>::infinity()) {
1148 double yaw_rate_in_degrees = yaw_rate * 180.0 / M_PI;
1149 // limit value range
1150 if (yaw_rate_in_degrees < CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE) {
1151 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE;
1152 } else if (yaw_rate_in_degrees > CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1153 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1154 }
1155
1156 object.z_angular_velocity.value.value = yaw_rate_in_degrees;
1157
1158 if(yaw_rate_std == std::numeric_limits<double>::infinity()) {
1159 object.z_angular_velocity.confidence.value = AngularSpeedConfidence::UNAVAILABLE;
1160 } else {
1161 yaw_rate_std *= 180.0 / M_PI;
1162 yaw_rate_std *= etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to degrees/s
1163 // How stupid is this?!
1164 static const std::map<double, uint8_t> confidence_map = {
1165 {1.0, AngularSpeedConfidence::DEG_SEC_01},
1166 {2.0, AngularSpeedConfidence::DEG_SEC_02},
1167 {5.0, AngularSpeedConfidence::DEG_SEC_05},
1168 {10.0, AngularSpeedConfidence::DEG_SEC_10},
1169 {20.0, AngularSpeedConfidence::DEG_SEC_20},
1170 {50.0, AngularSpeedConfidence::DEG_SEC_50},
1171 {std::numeric_limits<double>::infinity(), AngularSpeedConfidence::OUT_OF_RANGE},
1172 };
1173 for(const auto& [thresh, conf_val] : confidence_map) {
1174 if (yaw_rate_std <= thresh) {
1175 object.z_angular_velocity.confidence.value = conf_val;
1176 break;
1177 }
1178 }
1179 }
1180
1181 object.z_angular_velocity_is_present = true;
1182}
1183
1198inline void setObjectDimension(ObjectDimension& dimension, const double value,
1199 const double confidence = std::numeric_limits<double>::infinity()) {
1200 // limit value range
1201 if (value < ObjectDimensionValue::MIN || value > ObjectDimensionValue::MAX) {
1202 dimension.value.value = ObjectDimensionValue::OUT_OF_RANGE;
1203 } else {
1204 dimension.value.value = static_cast<uint16_t>(value);
1205 }
1206
1207 // limit confidence range
1208 if (confidence == std::numeric_limits<double>::infinity()) {
1209 dimension.confidence.value = ObjectDimensionConfidence::UNAVAILABLE;
1210 } else if (confidence > ObjectDimensionConfidence::MAX || confidence < ObjectDimensionConfidence::MIN) {
1211 dimension.confidence.value = ObjectDimensionConfidence::OUT_OF_RANGE;
1212 } else {
1213 dimension.confidence.value = static_cast<uint8_t>(confidence);
1214 }
1215
1216}
1217
1228inline void setXDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1229 const double std = std::numeric_limits<double>::infinity()) {
1230 setObjectDimension(object.object_dimension_x, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1231 object.object_dimension_x_is_present = true;
1232}
1233
1244inline void setYDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1245 const double std = std::numeric_limits<double>::infinity()) {
1246 setObjectDimension(object.object_dimension_y, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1247 object.object_dimension_y_is_present = true;
1248}
1249
1260inline void setZDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1261 const double std = std::numeric_limits<double>::infinity()) {
1262 setObjectDimension(object.object_dimension_z, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1263 object.object_dimension_z_is_present = true;
1264}
1265
1277inline void setDimensionsOfPerceivedObject(PerceivedObject& object, const gm::Vector3& dimensions,
1278 const double x_std = std::numeric_limits<double>::infinity(),
1279 const double y_std = std::numeric_limits<double>::infinity(),
1280 const double z_std = std::numeric_limits<double>::infinity()) {
1281 setXDimensionOfPerceivedObject(object, dimensions.x, x_std);
1282 setYDimensionOfPerceivedObject(object, dimensions.y, y_std);
1283 setZDimensionOfPerceivedObject(object, dimensions.z, z_std);
1284}
1285
1295inline void initPerceivedObject(PerceivedObject& object, const gm::Point& point, const int16_t delta_time = 0) {
1296 setPositionOfPerceivedObject(object, point);
1297 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1298}
1299
1312inline void initPerceivedObjectWithUTMPosition(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1313 const gm::PointStamped& point, const int16_t delta_time = 0) {
1314 setUTMPositionOfPerceivedObject(cpm, object, point);
1315 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1316}
1317
1327inline void initPerceivedObjectContainer(WrappedCpmContainer& container, const uint8_t n_objects = 0) {
1328 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER;
1329 container.container_data_perceived_object_container.number_of_perceived_objects.value = n_objects;
1330}
1331
1345inline void addPerceivedObjectToContainer(WrappedCpmContainer& container, const PerceivedObject& perceived_object) {
1346 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER) {
1347 container.container_data_perceived_object_container.perceived_objects.array.push_back(perceived_object);
1348 container.container_data_perceived_object_container.number_of_perceived_objects.value =
1349 container.container_data_perceived_object_container.perceived_objects.array.size();
1350 } else {
1351 throw std::invalid_argument("Container is not a PerceivedObjectContainer");
1352 }
1353}
1354
1367inline void addContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1368 // check for maximum number of containers
1369 if (cpm.payload.cpm_containers.value.array.size() < WrappedCpmContainers::MAX_SIZE) {
1370 cpm.payload.cpm_containers.value.array.push_back(container);
1371 } else {
1372 throw std::invalid_argument("Maximum number of CPM-Containers reached");
1373 }
1374}
1375
1384inline void setWGSRefPosConfidence(CollectivePerceptionMessage& cpm, const std::array<double, 4>& covariance_matrix) {
1385 setWGSPosConfidenceEllipse(cpm.payload.management_container.reference_position.position_confidence_ellipse,
1386 covariance_matrix);
1387}
1388
1397inline void initSensorInformationContainer(WrappedCpmContainer& container) {
1398 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER;
1399 container.container_data_sensor_information_container.array = std::vector<SensorInformation>();
1400}
1401
1412inline void setSensorID(SensorInformation& sensor_information, const uint8_t sensor_id = 0) {
1413 throwIfOutOfRange(sensor_id, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1414 sensor_information.sensor_id.value = sensor_id;
1415}
1416
1427inline void setSensorType(SensorInformation& sensor_information, const uint8_t sensor_type = SensorType::UNDEFINED) {
1428 throwIfOutOfRange(sensor_type, SensorType::MIN, SensorType::MAX, "SensorType");
1429 sensor_information.sensor_type.value = sensor_type;
1430}
1431
1450inline void addSensorInformationToContainer(WrappedCpmContainer& container, const SensorInformation& sensor_information) {
1451 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1452 // check for maximum number of SensorInformation entries
1453 if (container.container_data_sensor_information_container.array.size() < SensorInformationContainer::MAX_SIZE ) {
1454 throwIfOutOfRange(sensor_information.sensor_id.value, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1455 throwIfOutOfRange(sensor_information.sensor_type.value, SensorType::MIN, SensorType::MAX, "SensorType");
1456 container.container_data_sensor_information_container.array.push_back(sensor_information);
1457 } else {
1458 throw std::invalid_argument("Maximum number of entries SensorInformationContainers reached");
1459 }
1460 } else {
1461 throw std::invalid_argument("Container is not a SensorInformationContainer");
1462 }
1463}
1464
1479inline void addSensorInformationContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1480 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1481 throwIfOutOfRange(container.container_data_sensor_information_container.array.size(),
1482 SensorInformationContainer::MIN_SIZE, SensorInformationContainer::MAX_SIZE, "SensorInformationContainer array size"
1483 );
1484 addContainerToCPM(cpm, container);
1485 } else {
1486 throw std::invalid_argument("Container is not a SensorInformationContainer");
1487 }
1488}
1489
1490} // namespace etsi_its_cpm_ts_msgs::access

◆ initPerceivedObjectWithUTMPosition()

void etsi_its_cpm_ts_msgs::access::initPerceivedObjectWithUTMPosition ( CollectivePerceptionMessage & cpm,
PerceivedObject & object,
const gm::PointStamped & point,
const int16_t delta_time = 0 )
inline

Initializes a PerceivedObject with the given point (utm-position) and delta time.

This function initializes a PerceivedObject within a position and measurement delta time. It sets the position of a perceived object using the provided UTM position and the CPM's reference position. It sets the measurement delta time using the provided delta_time value.

Parameters
cpmThe CPM to get the reference position from.
objectThe PerceivedObject to be initialized.
pointThe gm::PointStamped representing the UTM position of the object including the frame_id (utm_<zone><N/S>).
delta_timeThe measurement delta time in milliseconds (default: 0).

Definition at line 735 of file cpm_ts_setters.h.

736 {
737 throw std::invalid_argument("Container is not a SensorInformationContainer");
738 }
739}

◆ initSensorInformationContainer()

void etsi_its_cpm_ts_msgs::access::initSensorInformationContainer ( WrappedCpmContainer & container)
inline

Initializes a WrappedCpmContainer as a SensorInformationContainer.

This function sets the container ID to CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER and initializes an empty vector with SensorInformation.

Parameters
containerA reference to the WrappedCpmContainer to be initialized as a SensorInformationContainer.

Definition at line 820 of file cpm_ts_setters.h.

856 {
857
859
869inline void setItsPduHeader(CollectivePerceptionMessage& cpm, const uint32_t station_id,
870 const uint8_t protocol_version = 0) {
871 setItsPduHeader(cpm.header, MessageId::CPM, station_id, protocol_version);
872}
873
885inline void setReferenceTime(
886 CollectivePerceptionMessage& cpm, const uint64_t unix_nanosecs,
887 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
888 TimestampIts t_its;
889 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
890 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
891 cpm.payload.management_container.reference_time = t_its;
892}
893
905inline void setReferencePosition(CollectivePerceptionMessage& cpm, const double latitude, const double longitude,
906 const double altitude = AltitudeValue::UNAVAILABLE) {
907 setReferencePosition(cpm.payload.management_container.reference_position, latitude, longitude, altitude);
908}
909
922inline void setFromUTMPosition(CollectivePerceptionMessage& cpm, const gm::PointStamped& utm_position, const int& zone,
923 const bool& northp) {
924 setFromUTMPosition(cpm.payload.management_container.reference_position, utm_position, zone, northp);
925}
926
935inline void setIdOfPerceivedObject(PerceivedObject& object, const uint16_t id) {
936 object.object_id.value = id;
937 object.object_id_is_present = true;
938}
939
951inline void setMeasurementDeltaTimeOfPerceivedObject(PerceivedObject& object, const int16_t delta_time = 0) {
952 if (delta_time < DeltaTimeMilliSecondSigned::MIN || delta_time > DeltaTimeMilliSecondSigned::MAX) {
953 throw std::invalid_argument("MeasurementDeltaTime out of range");
954 } else {
955 object.measurement_delta_time.value = delta_time;
956 }
957}
958
972inline void setCartesianCoordinateWithConfidence(CartesianCoordinateWithConfidence& coordinate, const double value,
973 const double confidence = std::numeric_limits<double>::infinity()) {
974 // limit value range
975 if (value < CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE) {
976 coordinate.value.value = CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE;
977 } else if (value > CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE) {
978 coordinate.value.value = CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE;
979 } else {
980 coordinate.value.value = static_cast<int32_t>(value);
981 }
982
983 // limit confidence range
984 if (confidence == std::numeric_limits<double>::infinity()) {
985 coordinate.confidence.value = CoordinateConfidence::UNAVAILABLE;
986 } else if (confidence > CoordinateConfidence::MAX || confidence < CoordinateConfidence::MIN) {
987 coordinate.confidence.value = CoordinateConfidence::OUT_OF_RANGE;
988 } else {
989 coordinate.confidence.value = static_cast<uint16_t>(confidence);
990 }
991}
992
1004inline void setPositionOfPerceivedObject(PerceivedObject& object, const gm::Point& point,
1005 const double x_std = std::numeric_limits<double>::infinity(),
1006 const double y_std = std::numeric_limits<double>::infinity(),
1007 const double z_std = std::numeric_limits<double>::infinity()) {
1008 setCartesianCoordinateWithConfidence(object.position.x_coordinate, point.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1009 setCartesianCoordinateWithConfidence(object.position.y_coordinate, point.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1010 if (point.z != 0.0) {
1011 setCartesianCoordinateWithConfidence(object.position.z_coordinate, point.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1012 object.position.z_coordinate_is_present = true;
1013 }
1014}
1015
1031inline void setUTMPositionOfPerceivedObject(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1032 const gm::PointStamped& utm_position,
1033 const double x_std = std::numeric_limits<double>::infinity(),
1034 const double y_std = std::numeric_limits<double>::infinity(),
1035 const double z_std = std::numeric_limits<double>::infinity()) {
1036 gm::PointStamped reference_position = getUTMPosition(cpm);
1037 if (utm_position.header.frame_id != reference_position.header.frame_id) {
1038 throw std::invalid_argument("UTM-Position frame_id (" + utm_position.header.frame_id +
1039 ") does not match the reference position frame_id (" + reference_position.header.frame_id +
1040 ")");
1041 }
1042 setCartesianCoordinateWithConfidence(object.position.x_coordinate,
1043 (utm_position.point.x - reference_position.point.x) * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1044 setCartesianCoordinateWithConfidence(object.position.y_coordinate,
1045 (utm_position.point.y - reference_position.point.y) * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1046 if (utm_position.point.z != 0.0) {
1047 setCartesianCoordinateWithConfidence(object.position.z_coordinate,
1048 (utm_position.point.z - reference_position.point.z) * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1049 object.position.z_coordinate_is_present = true;
1050 }
1051}
1052
1064inline void setVelocityComponent(VelocityComponent& velocity, const double value,
1065 const double confidence = std::numeric_limits<double>::infinity()) {
1066 // limit value range
1067 if (value < VelocityComponentValue::NEGATIVE_OUT_OF_RANGE) {
1068 velocity.value.value = VelocityComponentValue::NEGATIVE_OUT_OF_RANGE;
1069 } else if (value > VelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1070 velocity.value.value = VelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1071 } else {
1072 velocity.value.value = static_cast<int16_t>(value);
1073 }
1074
1075 // limit confidence range
1076 if(confidence == std::numeric_limits<double>::infinity()) {
1077 velocity.confidence.value = SpeedConfidence::UNAVAILABLE;
1078 } else if (confidence > SpeedConfidence::MAX || confidence < SpeedConfidence::MIN) {
1079 velocity.confidence.value = SpeedConfidence::OUT_OF_RANGE;
1080 } else {
1081 velocity.confidence.value = static_cast<uint8_t>(confidence);
1082 }
1083}
1084
1097inline void setVelocityOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_velocity,
1098 const double x_std = std::numeric_limits<double>::infinity(),
1099 const double y_std = std::numeric_limits<double>::infinity(),
1100 const double z_std = std::numeric_limits<double>::infinity()) {
1101 object.velocity.choice = Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY;
1102 setVelocityComponent(object.velocity.cartesian_velocity.x_velocity, cartesian_velocity.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1103 setVelocityComponent(object.velocity.cartesian_velocity.y_velocity, cartesian_velocity.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1104 if (cartesian_velocity.z != 0.0) {
1105 setVelocityComponent(object.velocity.cartesian_velocity.z_velocity, cartesian_velocity.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1106 object.velocity.cartesian_velocity.z_velocity_is_present = true;
1107 }
1108 object.velocity_is_present = true;
1109}
1110
1122inline void setAccelerationComponent(AccelerationComponent& acceleration, const double value,
1123 const double confidence = std::numeric_limits<double>::infinity()) {
1124 // limit value range
1125 if (value < AccelerationValue::NEGATIVE_OUT_OF_RANGE) {
1126 acceleration.value.value = AccelerationValue::NEGATIVE_OUT_OF_RANGE;
1127 } else if (value > AccelerationValue::POSITIVE_OUT_OF_RANGE) {
1128 acceleration.value.value = AccelerationValue::POSITIVE_OUT_OF_RANGE;
1129 } else {
1130 acceleration.value.value = static_cast<int16_t>(value);
1131 }
1132
1133 // limit confidence range
1134 if(confidence == std::numeric_limits<double>::infinity()) {
1135 acceleration.confidence.value = AccelerationConfidence::UNAVAILABLE;
1136 } else if (confidence > AccelerationConfidence::MAX || confidence < AccelerationConfidence::MIN) {
1137 acceleration.confidence.value = AccelerationConfidence::OUT_OF_RANGE;
1138 } else {
1139 acceleration.confidence.value = static_cast<uint8_t>(confidence);
1140 }
1141}
1142
1155inline void setAccelerationOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_acceleration,
1156 const double x_std = std::numeric_limits<double>::infinity(),
1157 const double y_std = std::numeric_limits<double>::infinity(),
1158 const double z_std = std::numeric_limits<double>::infinity()) {
1159 object.acceleration.choice = Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION;
1160 setAccelerationComponent(object.acceleration.cartesian_acceleration.x_acceleration, cartesian_acceleration.x * 10,
1161 x_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1162 setAccelerationComponent(object.acceleration.cartesian_acceleration.y_acceleration, cartesian_acceleration.y * 10,
1163 y_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1164 if (cartesian_acceleration.z != 0.0) {
1165 setAccelerationComponent(object.acceleration.cartesian_acceleration.z_acceleration, cartesian_acceleration.z * 10,
1166 z_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1167 object.acceleration.cartesian_acceleration.z_acceleration_is_present = true;
1168 }
1169 object.acceleration_is_present = true;
1170}
1171
1182inline void setYawOfPerceivedObject(PerceivedObject& object, const double yaw,
1183 double yaw_std = std::numeric_limits<double>::infinity()) {
1184 // wrap angle to range [0, 360)
1185 double yaw_in_degrees = yaw * 180 / M_PI;
1186 while (yaw_in_degrees >= 360.0) yaw_in_degrees -= 360.0;
1187 while (yaw_in_degrees < 0.0) yaw_in_degrees += 360.0;
1188 object.angles.z_angle.value.value = yaw_in_degrees * 10;
1189
1190 if(yaw_std == std::numeric_limits<double>::infinity()) {
1191 object.angles.z_angle.confidence.value = AngleConfidence::UNAVAILABLE;
1192 } else {
1193 yaw_std *= 180.0 / M_PI;
1194 yaw_std *= 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to 0.1 degrees
1195
1196 if (yaw_std > AngleConfidence::MAX || yaw_std < AngleConfidence::MIN) {
1197 object.angles.z_angle.confidence.value = AngleConfidence::OUT_OF_RANGE;
1198 } else {
1199 object.angles.z_angle.confidence.value = static_cast<uint8_t>(yaw_std);
1200 }
1201 }
1202 object.angles_is_present = true;
1203}
1204
1216inline void setYawRateOfPerceivedObject(PerceivedObject& object, const double yaw_rate,
1217 double yaw_rate_std = std::numeric_limits<double>::infinity()) {
1218 double yaw_rate_in_degrees = yaw_rate * 180.0 / M_PI;
1219 // limit value range
1220 if (yaw_rate_in_degrees < CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE) {
1221 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE;
1222 } else if (yaw_rate_in_degrees > CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1223 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1224 }
1225
1226 object.z_angular_velocity.value.value = yaw_rate_in_degrees;
1227
1228 if(yaw_rate_std == std::numeric_limits<double>::infinity()) {
1229 object.z_angular_velocity.confidence.value = AngularSpeedConfidence::UNAVAILABLE;
1230 } else {
1231 yaw_rate_std *= 180.0 / M_PI;
1232 yaw_rate_std *= etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to degrees/s
1233 // How stupid is this?!
1234 static const std::map<double, uint8_t> confidence_map = {
1235 {1.0, AngularSpeedConfidence::DEG_SEC_01},
1236 {2.0, AngularSpeedConfidence::DEG_SEC_02},
1237 {5.0, AngularSpeedConfidence::DEG_SEC_05},
1238 {10.0, AngularSpeedConfidence::DEG_SEC_10},
1239 {20.0, AngularSpeedConfidence::DEG_SEC_20},
1240 {50.0, AngularSpeedConfidence::DEG_SEC_50},
1241 {std::numeric_limits<double>::infinity(), AngularSpeedConfidence::OUT_OF_RANGE},
1242 };
1243 for(const auto& [thresh, conf_val] : confidence_map) {
1244 if (yaw_rate_std <= thresh) {
1245 object.z_angular_velocity.confidence.value = conf_val;
1246 break;
1247 }
1248 }
1249 }
1250
1251 object.z_angular_velocity_is_present = true;
1252}
1253
1268inline void setObjectDimension(ObjectDimension& dimension, const double value,
1269 const double confidence = std::numeric_limits<double>::infinity()) {
1270 // limit value range
1271 if (value < ObjectDimensionValue::MIN || value > ObjectDimensionValue::MAX) {
1272 dimension.value.value = ObjectDimensionValue::OUT_OF_RANGE;
1273 } else {
1274 dimension.value.value = static_cast<uint16_t>(value);
1275 }
1276
1277 // limit confidence range
1278 if (confidence == std::numeric_limits<double>::infinity()) {
1279 dimension.confidence.value = ObjectDimensionConfidence::UNAVAILABLE;
1280 } else if (confidence > ObjectDimensionConfidence::MAX || confidence < ObjectDimensionConfidence::MIN) {
1281 dimension.confidence.value = ObjectDimensionConfidence::OUT_OF_RANGE;
1282 } else {
1283 dimension.confidence.value = static_cast<uint8_t>(confidence);
1284 }
1285
1286}
1287
1298inline void setXDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1299 const double std = std::numeric_limits<double>::infinity()) {
1300 setObjectDimension(object.object_dimension_x, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1301 object.object_dimension_x_is_present = true;
1302}
1303
1314inline void setYDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1315 const double std = std::numeric_limits<double>::infinity()) {
1316 setObjectDimension(object.object_dimension_y, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1317 object.object_dimension_y_is_present = true;
1318}
1319
1330inline void setZDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1331 const double std = std::numeric_limits<double>::infinity()) {
1332 setObjectDimension(object.object_dimension_z, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1333 object.object_dimension_z_is_present = true;
1334}
1335
1347inline void setDimensionsOfPerceivedObject(PerceivedObject& object, const gm::Vector3& dimensions,
1348 const double x_std = std::numeric_limits<double>::infinity(),
1349 const double y_std = std::numeric_limits<double>::infinity(),
1350 const double z_std = std::numeric_limits<double>::infinity()) {
1351 setXDimensionOfPerceivedObject(object, dimensions.x, x_std);
1352 setYDimensionOfPerceivedObject(object, dimensions.y, y_std);
1353 setZDimensionOfPerceivedObject(object, dimensions.z, z_std);
1354}
1355
1365inline void initPerceivedObject(PerceivedObject& object, const gm::Point& point, const int16_t delta_time = 0) {
1366 setPositionOfPerceivedObject(object, point);
1367 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1368}
1369
1382inline void initPerceivedObjectWithUTMPosition(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1383 const gm::PointStamped& point, const int16_t delta_time = 0) {
1384 setUTMPositionOfPerceivedObject(cpm, object, point);
1385 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1386}
1387
1397inline void initPerceivedObjectContainer(WrappedCpmContainer& container, const uint8_t n_objects = 0) {
1398 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER;
1399 container.container_data_perceived_object_container.number_of_perceived_objects.value = n_objects;
1400}
1401
1415inline void addPerceivedObjectToContainer(WrappedCpmContainer& container, const PerceivedObject& perceived_object) {
1416 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER) {
1417 container.container_data_perceived_object_container.perceived_objects.array.push_back(perceived_object);
1418 container.container_data_perceived_object_container.number_of_perceived_objects.value =
1419 container.container_data_perceived_object_container.perceived_objects.array.size();
1420 } else {
1421 throw std::invalid_argument("Container is not a PerceivedObjectContainer");
1422 }
1423}
1424
1437inline void addContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1438 // check for maximum number of containers
1439 if (cpm.payload.cpm_containers.value.array.size() < WrappedCpmContainers::MAX_SIZE) {
1440 cpm.payload.cpm_containers.value.array.push_back(container);
1441 } else {
1442 throw std::invalid_argument("Maximum number of CPM-Containers reached");
1443 }
1444}
1445
1454inline void setWGSRefPosConfidence(CollectivePerceptionMessage& cpm, const std::array<double, 4>& covariance_matrix) {
1455 setWGSPosConfidenceEllipse(cpm.payload.management_container.reference_position.position_confidence_ellipse,
1456 covariance_matrix);
1457}
1458
1467inline void initSensorInformationContainer(WrappedCpmContainer& container) {
1468 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER;
1469 container.container_data_sensor_information_container.array = std::vector<SensorInformation>();
1470}
1471
1482inline void setSensorID(SensorInformation& sensor_information, const uint8_t sensor_id = 0) {
1483 throwIfOutOfRange(sensor_id, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1484 sensor_information.sensor_id.value = sensor_id;
1485}
1486
1497inline void setSensorType(SensorInformation& sensor_information, const uint8_t sensor_type = SensorType::UNDEFINED) {
1498 throwIfOutOfRange(sensor_type, SensorType::MIN, SensorType::MAX, "SensorType");
1499 sensor_information.sensor_type.value = sensor_type;
1500}
1501
1520inline void addSensorInformationToContainer(WrappedCpmContainer& container, const SensorInformation& sensor_information) {
1521 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1522 // check for maximum number of SensorInformation entries
1523 if (container.container_data_sensor_information_container.array.size() < SensorInformationContainer::MAX_SIZE ) {
1524 throwIfOutOfRange(sensor_information.sensor_id.value, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1525 throwIfOutOfRange(sensor_information.sensor_type.value, SensorType::MIN, SensorType::MAX, "SensorType");
1526 container.container_data_sensor_information_container.array.push_back(sensor_information);
1527 } else {
1528 throw std::invalid_argument("Maximum number of entries SensorInformationContainers reached");
1529 }
1530 } else {
1531 throw std::invalid_argument("Container is not a SensorInformationContainer");
1532 }
1533}
1534
1549inline void addSensorInformationContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1550 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1551 throwIfOutOfRange(container.container_data_sensor_information_container.array.size(),
1552 SensorInformationContainer::MIN_SIZE, SensorInformationContainer::MAX_SIZE, "SensorInformationContainer array size"
1553 );
1554 addContainerToCPM(cpm, container);
1555 } else {
1556 throw std::invalid_argument("Container is not a SensorInformationContainer");
1557 }
1558}
1559
1560} // namespace etsi_its_cpm_ts_msgs::access

◆ setAccelerationComponent()

void etsi_its_cpm_ts_msgs::access::setAccelerationComponent ( AccelerationComponent & acceleration,
const double value,
const double confidence = std::numeric_limits<double>::infinity() )
inline

Sets the value and confidence of a AccelerationComponent.

This function sets the value and confidence of a AccelerationComponent object. The value is limited to a specific range, and the confidence is limited to a specific range as well. If the provided value or confidence is out of range, it will be set to the corresponding out-of-range value.

Parameters
accelerationThe AccelerationComponent object to set the value and confidence for.
valueThe value to set for the AccelerationComponent in dm/s^2.
confidenceThe confidence to set for the AccelerationComponent in dm/s^2. Default value is infinity, mapping to AccelerationConfidence::UNAVAILABLE.

Definition at line 475 of file cpm_ts_setters.h.

480 {
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

◆ setAccelerationConfidence()

template<typename AccelerationConfidence>
void etsi_its_cpm_ts_msgs::access::setAccelerationConfidence ( AccelerationConfidence & accel_confidence,
const double value )
inline

Set the Acceleration Confidence object.

Parameters
accel_confidenceobject to set
valuestandard deviation in m/s^2 as decimal number

Definition at line 220 of file cpm_ts_setters.h.

227 {
228 setCartesianCoordinateWithConfidence(object.position.z_coordinate,

◆ setAccelerationOfPerceivedObject()

void etsi_its_cpm_ts_msgs::access::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() )
inline

Sets the acceleration of a perceived object.

This function sets the acceleration of a perceived object using the provided Cartesian acceleration components. Optionally, confidence values can be specified for each acceleration component.

Parameters
objectThe perceived object for which the acceleration is being set.
cartesian_accelerationThe Cartesian acceleration components (x, y, z) of the object (in m/s^2).
x_stdThe standard deviation in m/s^2 for the x acceleration component (default: infinity).
y_stdThe standard deviation in m/s^2 for the y acceleration component (default: infinity).
z_stdThe standard deviation in m/s^2 for the z acceleration component (default: infinity).

Definition at line 508 of file cpm_ts_setters.h.

512 {
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

◆ setAltitude()

void etsi_its_cpm_ts_msgs::access::setAltitude ( Altitude & altitude,
const double value )
inline

Set the Altitude object.

AltitudeConfidence is set to UNAVAILABLE

Parameters
altitudeobject to set
valueAltitude value (above the reference ellipsoid surface) in meter as decimal number

Definition at line 166 of file cpm_ts_setters.h.

◆ setAltitudeValue()

void etsi_its_cpm_ts_msgs::access::setAltitudeValue ( AltitudeValue & altitude,
const double value )
inline

Set the AltitudeValue object.

Parameters
altitudeobject to set
valueAltitudeValue value (above the reference ellipsoid surface) in meter as decimal number

Definition at line 147 of file cpm_ts_setters.h.

◆ setCartesianCoordinateWithConfidence()

void etsi_its_cpm_ts_msgs::access::setCartesianCoordinateWithConfidence ( CartesianCoordinateWithConfidence & coordinate,
const double value,
const double confidence = std::numeric_limits<double>::infinity() )
inline

Sets the value and confidence of a CartesianCoordinateWithConfidence object.

This function sets the value and confidence of a CartesianCoordinateWithConfidence object. The value is limited to the range defined by CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE and CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE. The confidence is limited to the range defined by CoordinateConfidence::MIN and CoordinateConfidence::MAX. If the provided confidence is out of range, the confidence value is set to CoordinateConfidence::OUT_OF_RANGE.

Parameters
coordinateThe CartesianCoordinateWithConfidence object to be modified.
valueThe value to be set in centimeters.
confidenceThe confidence to be set in centimeters (default: infinity, which will map to CoordinateConfidence::UNAVAILABLE).

Definition at line 325 of file cpm_ts_setters.h.

◆ setDimensionsOfPerceivedObject()

void etsi_its_cpm_ts_msgs::access::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() )
inline

Sets all dimensions of a perceived object.

This function sets the dimensions of a perceived object using the provided dimensions and confidence values.

Parameters
objectThe perceived object to set the dimensions for.
dimensionsThe dimensions of the object as a gm::Vector3 (x, y, z) in meters.
x_stdThe standard deviation in meters for the x dimension (optional, default: infinity).
y_stdThe standard deviation in meters for the y dimension (optional, default: infinity).
z_stdThe standard deviation in meters for the z dimension (optional, default: infinity).

Definition at line 700 of file cpm_ts_setters.h.

◆ setFromUTMPosition() [1/2]

void etsi_its_cpm_ts_msgs::access::setFromUTMPosition ( CollectivePerceptionMessage & cpm,
const gm::PointStamped & utm_position,
const int & zone,
const bool & northp )
inline

Set the ReferencePosition of a CPM from a given UTM-Position.

The position is transformed to latitude and longitude by using GeographicLib::UTMUPS The z-Coordinate is directly used as altitude value The frame_id of the given utm_position must be set to 'utm_<zone><N/S>'

Parameters
[out]cpmCPM for which to set the ReferencePosition
[in]utm_positiongeometry_msgs::PointStamped describing the given utm position in meters
[in]zonethe UTM zone (zero means UPS) of the given position
[in]northphemisphere (true means north, false means south)

Definition at line 275 of file cpm_ts_setters.h.

◆ setFromUTMPosition() [2/2]

template<typename T>
void etsi_its_cpm_ts_msgs::access::setFromUTMPosition ( T & reference_position,
const gm::PointStamped & utm_position,
const int zone,
const bool northp )
inline

Set the ReferencePosition from a given UTM-Position.

The position is transformed to latitude and longitude by using GeographicLib::UTMUPS The z-Coordinate is directly used as altitude value The frame_id of the given utm_position must be set to 'utm_<zone><N/S>'

Parameters
[out]reference_positionReferencePostion or ReferencePositionWithConfidence to set
[in]utm_positiongeometry_msgs::PointStamped describing the given utm position
[in]zonethe UTM zone (zero means UPS) of the given position
[in]northphemisphere (true means north, false means south)

Definition at line 268 of file cpm_ts_setters.h.

◆ setHeadingCDD()

template<typename Heading, typename HeadingConfidence = decltype(Heading::heading_confidence)>
void etsi_its_cpm_ts_msgs::access::setHeadingCDD ( Heading & heading,
const double value,
double confidence = std::numeric_limits<double>::infinity() )

Set the Heading object.

0.0° equals WGS84 North, 90.0° equals WGS84 East, 180.0° equals WGS84 South and 270.0° equals WGS84 West HeadingConfidence is set to UNAVAILABLE

Parameters
headingobject to set
valueHeading value in degree as decimal number
confidencestandard deviation of heading in degree as decimal number (default: infinity, mapping to HeadingConfidence::UNAVAILABLE)

Definition at line 327 of file cpm_ts_setters.h.

◆ setHeadingConfidence()

template<typename HeadingConfidence>
void etsi_its_cpm_ts_msgs::access::setHeadingConfidence ( HeadingConfidence & heading_confidence,
const double value )
inline

Set the Heading Confidence object.

Parameters
heading_confidenceobject to set
valuestandard deviation of heading in degree as decimal number

Definition at line 306 of file cpm_ts_setters.h.

◆ setHeadingValue()

template<typename HeadingValue>
void etsi_its_cpm_ts_msgs::access::setHeadingValue ( HeadingValue & heading,
const double value )
inline

Set the HeadingValue object.

0.0° equals WGS84 North, 90.0° equals WGS84 East, 180.0° equals WGS84 South and 270.0° equals WGS84 West

Parameters
headingobject to set
valueHeading value in degree as decimal number

Definition at line 293 of file cpm_ts_setters.h.

◆ setIdOfPerceivedObject()

void etsi_its_cpm_ts_msgs::access::setIdOfPerceivedObject ( PerceivedObject & object,
const uint16_t id )
inline

Set the ID of a PerceivedObject.

Sets the object_id of the PerceivedObject to the given ID.

Parameters
objectPerceivedObject to set the ID for
idID to set

Definition at line 288 of file cpm_ts_setters.h.

◆ setItsPduHeader() [1/2]

void etsi_its_cpm_ts_msgs::access::setItsPduHeader ( CollectivePerceptionMessage & cpm,
const uint32_t station_id,
const uint8_t protocol_version = 0 )
inline

Sets the ITS PDU header of a CPM.

This function sets the ITS PDU header of a CPM with the provided station ID and protocol version.

Parameters
cpmThe CPM to set the ITS PDU header for.
station_idThe station ID to set in the ITS PDU header.
protocol_versionThe protocol version to set in the ITS PDU header. Default is 0.

Definition at line 222 of file cpm_ts_setters.h.

◆ setItsPduHeader() [2/2]

void etsi_its_cpm_ts_msgs::access::setItsPduHeader ( ItsPduHeader & header,
const uint8_t message_id,
const uint32_t station_id,
const uint8_t protocol_version = 0 )
inline

Set the Its Pdu Header object.

Parameters
headerItsPduHeader to be set
message_idID of the message
station_id
protocol_version

Definition at line 85 of file cpm_ts_setters.h.

◆ setLateralAcceleration()

void etsi_its_cpm_ts_msgs::access::setLateralAcceleration ( AccelerationComponent & accel,
const double value,
const double confidence )
inline

Set the LateralAcceleration object.

AccelerationConfidence is set to UNAVAILABLE

Parameters
accelobject to set
valueLaterallAccelerationValue in m/s^2 as decimal number (left is positive)

Definition at line 160 of file cpm_ts_setters.h.

◆ setLateralAccelerationValue()

void etsi_its_cpm_ts_msgs::access::setLateralAccelerationValue ( AccelerationValue & accel,
const double value )
inline

Set the LateralAccelerationValue object.

Parameters
accelobject to set
valueLateralAccelerationValue in m/s^2 as decimal number (left is positive)

Definition at line 141 of file cpm_ts_setters.h.

◆ setLatitude()

void etsi_its_cpm_ts_msgs::access::setLatitude ( Latitude & latitude,
const double deg )
inline

Set the Latitude object.

Parameters
latitudeobject to set
degLatitude value in degree as decimal number

Definition at line 123 of file cpm_ts_setters.h.

◆ setLongitude()

void etsi_its_cpm_ts_msgs::access::setLongitude ( Longitude & longitude,
const double deg )
inline

Set the Longitude object.

Parameters
longitudeobject to set
degLongitude value in degree as decimal number

Definition at line 135 of file cpm_ts_setters.h.

◆ setLongitudinalAcceleration()

void etsi_its_cpm_ts_msgs::access::setLongitudinalAcceleration ( AccelerationComponent & accel,
const double value,
const double confidence )
inline

Set the LongitudinalAcceleration object.

AccelerationConfidence is set to UNAVAILABLE

Parameters
accelobject to set
valueLongitudinalAccelerationValue in m/s^2 as decimal number (braking is negative)

Definition at line 130 of file cpm_ts_setters.h.

◆ setLongitudinalAccelerationValue()

void etsi_its_cpm_ts_msgs::access::setLongitudinalAccelerationValue ( AccelerationValue & accel,
const double value )
inline

Set the LongitudinalAccelerationValue object.

Parameters
accelobject to set
valueLongitudinalAccelerationValue in m/s^2 as decimal number (braking is negative)

Definition at line 111 of file cpm_ts_setters.h.

◆ setMeasurementDeltaTimeOfPerceivedObject()

void etsi_its_cpm_ts_msgs::access::setMeasurementDeltaTimeOfPerceivedObject ( PerceivedObject & object,
const int16_t delta_time = 0 )
inline

Sets the measurement delta time of a PerceivedObject.

This function sets the measurement delta time of a PerceivedObject. The measurement delta time represents the time difference between the reference time of the CPM and the measurement of the object.

Parameters
objectThe PerceivedObject to set the measurement delta time for.
delta_timeThe measurement delta time to set in milliseconds. Default value is 0.
Exceptions
std::invalid_argumentif the delta_time is out of range.

Definition at line 304 of file cpm_ts_setters.h.

◆ setObjectDimension()

void etsi_its_cpm_ts_msgs::access::setObjectDimension ( ObjectDimension & dimension,
const double value,
const double confidence = std::numeric_limits<double>::infinity() )
inline

Sets the object dimension with the given value and confidence.

This function sets the value and confidence of the object dimension based on the provided parameters. The value is limited to the range defined by ObjectDimensionValue::MIN and ObjectDimensionValue::MAX. If the provided value is outside this range, the dimension value is set to ObjectDimensionValue::OUT_OF_RANGE.

The confidence is limited to the range defined by ObjectDimensionConfidence::MIN and ObjectDimensionConfidence::MAX. If the provided confidence is outside this range, the confidence value is set to ObjectDimensionConfidence::OUT_OF_RANGE.

Parameters
dimensionThe object dimension to be set.
valueThe value of the object dimension in decimeters.
confidenceThe confidence of the object dimension in decimeters (optional, default is infinty, mapping to ObjectDimensionConfidence::UNAVAILABLE).

Definition at line 621 of file cpm_ts_setters.h.

635inline 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
void setWGSPosConfidenceEllipse(PosConfidenceEllipse &position_confidence_ellipse, const std::array< double, 4 > &covariance_matrix)
Set the Pos Confidence Ellipse object.

◆ setPosConfidenceEllipse() [1/2]

template<typename PosConfidenceEllipse>
void etsi_its_cpm_ts_msgs::access::setPosConfidenceEllipse ( PosConfidenceEllipse & position_confidence_ellipse,
const double semi_major_axis,
const double semi_minor_axis,
const double orientation )
inline

Set the Pos Confidence Ellipse object.

Parameters
[out]position_confidence_ellipseThe PosConfidenceEllipse to set
[in]semi_major_axislength of the semi-major axis in meters
[in]semi_minor_axislength of the semi-minor axis in meters
[in]orientationof the semi-major axis in degrees, with respect to WGS84

Definition at line 360 of file cpm_ts_setters.h.

364 {
365 // wrap angle to range [0, 360)

◆ setPosConfidenceEllipse() [2/2]

template<typename PosConfidenceEllipse>
void etsi_its_cpm_ts_msgs::access::setPosConfidenceEllipse ( PosConfidenceEllipse & position_confidence_ellipse,
const std::array< double, 4 > & covariance_matrix,
const double object_heading )
inline

Set the Pos Confidence Ellipse object.

Parameters
position_confidence_ellipse
covariance_matrixThe four values of the covariance matrix in the order: cov_xx, cov_xy, cov_yx, cov_yy The matrix has to be SPD, otherwise a std::invalid_argument exception is thrown. Its coordinate system is aligned with the object (x = longitudinal, y = lateral)
object_headingThe heading of the object in rad, with respect to WGS84

Definition at line 433 of file cpm_ts_setters.h.

◆ setPositionConfidenceEllipse() [1/2]

template<typename PositionConfidenceEllipse, typename Wgs84AngleValue = decltype(PositionConfidenceEllipse::semi_major_axis_orientation)>
void etsi_its_cpm_ts_msgs::access::setPositionConfidenceEllipse ( PositionConfidenceEllipse & position_confidence_ellipse,
const double semi_major_axis,
const double semi_minor_axis,
const double orientation )
inline

Set the Position Confidence Ellipse object.

Parameters
position_confidence_ellipseThe position confidence ellipse to set
semi_major_axisThe length of the semi-major axis in meters
semi_minor_axisThe length of the semi-minor axis in meters
orientationThe orientation of the semi-major axis in degrees, relative to WGS84

Definition at line 174 of file cpm_ts_setters.h.

◆ setPositionConfidenceEllipse() [2/2]

template<typename PositionConfidenceEllipse>
void etsi_its_cpm_ts_msgs::access::setPositionConfidenceEllipse ( PositionConfidenceEllipse & position_confidence_ellipse,
const std::array< double, 4 > & covariance_matrix,
const double object_heading )
inline

Set the Position Confidence Ellipse object.

Parameters
position_confidence_ellipse
covariance_matrixThe four values of the covariance matrix in the order: cov_xx, cov_xy, cov_yx, cov_yy The matrix has to be SPD, otherwise a std::invalid_argument exception is thrown. Its coordinate system is aligned with the object (x = longitudinal, y = lateral)
object_headingThe heading of the object in rad, with respect to WGS84

Definition at line 191 of file cpm_ts_setters.h.

191 {
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 }

◆ setPositionOfPerceivedObject()

void etsi_its_cpm_ts_msgs::access::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() )
inline

Sets the position of a perceived object (relative to the CPM's reference position).

This function sets the position of a perceived object using the provided coordinates and confidence values.

Parameters
objectThe PerceivedObject to set the position for.
pointThe gm::Point representing the coordinates of the object in meters.
x_stdThe standard deviation in meters for the x-coordinate (default: infinity).
y_stdThe standard deviation in meters for the y-coordinate (default: infinity).
z_stdThe standard deviation in meters for the z-coordinate (default: infinity).

Definition at line 357 of file cpm_ts_setters.h.

364 {
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;

◆ setReferencePosition() [1/2]

void etsi_its_cpm_ts_msgs::access::setReferencePosition ( CollectivePerceptionMessage & cpm,
const double latitude,
const double longitude,
const double altitude = AltitudeValue::UNAVAILABLE )
inline

Set the ReferencePositionWithConfidence for a CPM TS.

This function sets the latitude, longitude, and altitude of the CPMs reference position. If the altitude is not provided, it is set to AltitudeValue::UNAVAILABLE.

Parameters
cpmCPM to set the ReferencePosition
latitudeThe latitude value position in degree as decimal number.
longitudeThe longitude value in degree as decimal number.
altitudeThe altitude value (above the reference ellipsoid surface) in meter as decimal number (optional).

Definition at line 258 of file cpm_ts_setters.h.

259 {
260 velocity.confidence.value = SpeedConfidence::OUT_OF_RANGE;
261 } else {

◆ setReferencePosition() [2/2]

template<typename T>
void etsi_its_cpm_ts_msgs::access::setReferencePosition ( T & ref_position,
const double latitude,
const double longitude,
const double altitude = AltitudeValue::UNAVAILABLE )
inline

Sets the reference position in the given ReferencePostion object.

This function sets the latitude, longitude, and altitude of the reference position. If the altitude is not provided, it is set to AltitudeValue::UNAVAILABLE.

Parameters
ref_positionReferencePostion or ReferencePositionWithConfidence object to set the reference position in.
latitudeThe latitude value position in degree as decimal number.
longitudeThe longitude value in degree as decimal number.
altitudeThe altitude value (above the reference ellipsoid surface) in meter as decimal number (optional).

Definition at line 242 of file cpm_ts_setters.h.

246 {
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);

◆ setReferenceTime()

void etsi_its_cpm_ts_msgs::access::setReferenceTime ( CollectivePerceptionMessage & cpm,
const uint64_t unix_nanosecs,
const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second )
inline

Sets the reference time in a CPM.

This function sets the reference time in a CPM object. The reference time is represented by a Unix timestamp in nanoseconds including the number of leap seconds. The reference time is stored in the payload management container of the CPM.

Parameters
cpmThe CPM object to set the reference time in.
unix_nanosecsThe Unix timestamp in nanoseconds representing the reference time.
n_leap_secondsThe number of leap seconds to be considered. Defaults to the todays number of leap seconds since 2004.

Definition at line 238 of file cpm_ts_setters.h.

◆ setSemiAxis()

template<typename SemiAxisLength>
void etsi_its_cpm_ts_msgs::access::setSemiAxis ( SemiAxisLength & semi_axis_length,
const double length )
inline

Set the Semi Axis length.

// See https://godbolt.org/z/Eceavfo99 on how the OneCentimeterHelper works with this template

Parameters
semi_axis_lengthThe SemiAxisLength to set
lengththe desired length in meters

Definition at line 341 of file cpm_ts_setters.h.

345 {
346 setAccelerationComponent(object.acceleration.cartesian_acceleration.z_acceleration, cartesian_acceleration.z * 10,
347 z_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
348 object.acceleration.cartesian_acceleration.z_acceleration_is_present = true;
349 }

◆ setSensorID()

void etsi_its_cpm_ts_msgs::access::setSensorID ( SensorInformation & sensor_information,
const uint8_t sensor_id = 0 )
inline

Sets the sensorId of a SensorInformation object.

This function sets the sensorId of a SensorInformation object. The sensorId is limited to the range defined by Identifier1B::MIN and Identifier1B::MAX.

Parameters
sensor_informationThe SensorInformation object to set the sensorId for.
sensor_idThe sensorId to set (default: 0).
Exceptions
std::invalid_argumentif the sensor_id is out of range.

Definition at line 835 of file cpm_ts_setters.h.

871 {
872
874
884inline void setItsPduHeader(CollectivePerceptionMessage& cpm, const uint32_t station_id,
885 const uint8_t protocol_version = 0) {
886 setItsPduHeader(cpm.header, MessageId::CPM, station_id, protocol_version);
887}
888
900inline void setReferenceTime(
901 CollectivePerceptionMessage& cpm, const uint64_t unix_nanosecs,
902 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
903 TimestampIts t_its;
904 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
905 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
906 cpm.payload.management_container.reference_time = t_its;
907}
908
920inline void setReferencePosition(CollectivePerceptionMessage& cpm, const double latitude, const double longitude,
921 const double altitude = AltitudeValue::UNAVAILABLE) {
922 setReferencePosition(cpm.payload.management_container.reference_position, latitude, longitude, altitude);
923}
924
937inline void setFromUTMPosition(CollectivePerceptionMessage& cpm, const gm::PointStamped& utm_position, const int& zone,
938 const bool& northp) {
939 setFromUTMPosition(cpm.payload.management_container.reference_position, utm_position, zone, northp);
940}
941
950inline void setIdOfPerceivedObject(PerceivedObject& object, const uint16_t id) {
951 object.object_id.value = id;
952 object.object_id_is_present = true;
953}
954
966inline void setMeasurementDeltaTimeOfPerceivedObject(PerceivedObject& object, const int16_t delta_time = 0) {
967 if (delta_time < DeltaTimeMilliSecondSigned::MIN || delta_time > DeltaTimeMilliSecondSigned::MAX) {
968 throw std::invalid_argument("MeasurementDeltaTime out of range");
969 } else {
970 object.measurement_delta_time.value = delta_time;
971 }
972}
973
987inline void setCartesianCoordinateWithConfidence(CartesianCoordinateWithConfidence& coordinate, const double value,
988 const double confidence = std::numeric_limits<double>::infinity()) {
989 // limit value range
990 if (value < CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE) {
991 coordinate.value.value = CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE;
992 } else if (value > CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE) {
993 coordinate.value.value = CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE;
994 } else {
995 coordinate.value.value = static_cast<int32_t>(value);
996 }
997
998 // limit confidence range
999 if (confidence == std::numeric_limits<double>::infinity()) {
1000 coordinate.confidence.value = CoordinateConfidence::UNAVAILABLE;
1001 } else if (confidence > CoordinateConfidence::MAX || confidence < CoordinateConfidence::MIN) {
1002 coordinate.confidence.value = CoordinateConfidence::OUT_OF_RANGE;
1003 } else {
1004 coordinate.confidence.value = static_cast<uint16_t>(confidence);
1005 }
1006}
1007
1019inline void setPositionOfPerceivedObject(PerceivedObject& object, const gm::Point& point,
1020 const double x_std = std::numeric_limits<double>::infinity(),
1021 const double y_std = std::numeric_limits<double>::infinity(),
1022 const double z_std = std::numeric_limits<double>::infinity()) {
1023 setCartesianCoordinateWithConfidence(object.position.x_coordinate, point.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1024 setCartesianCoordinateWithConfidence(object.position.y_coordinate, point.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1025 if (point.z != 0.0) {
1026 setCartesianCoordinateWithConfidence(object.position.z_coordinate, point.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1027 object.position.z_coordinate_is_present = true;
1028 }
1029}
1030
1046inline void setUTMPositionOfPerceivedObject(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1047 const gm::PointStamped& utm_position,
1048 const double x_std = std::numeric_limits<double>::infinity(),
1049 const double y_std = std::numeric_limits<double>::infinity(),
1050 const double z_std = std::numeric_limits<double>::infinity()) {
1051 gm::PointStamped reference_position = getUTMPosition(cpm);
1052 if (utm_position.header.frame_id != reference_position.header.frame_id) {
1053 throw std::invalid_argument("UTM-Position frame_id (" + utm_position.header.frame_id +
1054 ") does not match the reference position frame_id (" + reference_position.header.frame_id +
1055 ")");
1056 }
1057 setCartesianCoordinateWithConfidence(object.position.x_coordinate,
1058 (utm_position.point.x - reference_position.point.x) * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1059 setCartesianCoordinateWithConfidence(object.position.y_coordinate,
1060 (utm_position.point.y - reference_position.point.y) * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1061 if (utm_position.point.z != 0.0) {
1062 setCartesianCoordinateWithConfidence(object.position.z_coordinate,
1063 (utm_position.point.z - reference_position.point.z) * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1064 object.position.z_coordinate_is_present = true;
1065 }
1066}
1067
1079inline void setVelocityComponent(VelocityComponent& velocity, const double value,
1080 const double confidence = std::numeric_limits<double>::infinity()) {
1081 // limit value range
1082 if (value < VelocityComponentValue::NEGATIVE_OUT_OF_RANGE) {
1083 velocity.value.value = VelocityComponentValue::NEGATIVE_OUT_OF_RANGE;
1084 } else if (value > VelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1085 velocity.value.value = VelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1086 } else {
1087 velocity.value.value = static_cast<int16_t>(value);
1088 }
1089
1090 // limit confidence range
1091 if(confidence == std::numeric_limits<double>::infinity()) {
1092 velocity.confidence.value = SpeedConfidence::UNAVAILABLE;
1093 } else if (confidence > SpeedConfidence::MAX || confidence < SpeedConfidence::MIN) {
1094 velocity.confidence.value = SpeedConfidence::OUT_OF_RANGE;
1095 } else {
1096 velocity.confidence.value = static_cast<uint8_t>(confidence);
1097 }
1098}
1099
1112inline void setVelocityOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_velocity,
1113 const double x_std = std::numeric_limits<double>::infinity(),
1114 const double y_std = std::numeric_limits<double>::infinity(),
1115 const double z_std = std::numeric_limits<double>::infinity()) {
1116 object.velocity.choice = Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY;
1117 setVelocityComponent(object.velocity.cartesian_velocity.x_velocity, cartesian_velocity.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1118 setVelocityComponent(object.velocity.cartesian_velocity.y_velocity, cartesian_velocity.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1119 if (cartesian_velocity.z != 0.0) {
1120 setVelocityComponent(object.velocity.cartesian_velocity.z_velocity, cartesian_velocity.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1121 object.velocity.cartesian_velocity.z_velocity_is_present = true;
1122 }
1123 object.velocity_is_present = true;
1124}
1125
1137inline void setAccelerationComponent(AccelerationComponent& acceleration, const double value,
1138 const double confidence = std::numeric_limits<double>::infinity()) {
1139 // limit value range
1140 if (value < AccelerationValue::NEGATIVE_OUT_OF_RANGE) {
1141 acceleration.value.value = AccelerationValue::NEGATIVE_OUT_OF_RANGE;
1142 } else if (value > AccelerationValue::POSITIVE_OUT_OF_RANGE) {
1143 acceleration.value.value = AccelerationValue::POSITIVE_OUT_OF_RANGE;
1144 } else {
1145 acceleration.value.value = static_cast<int16_t>(value);
1146 }
1147
1148 // limit confidence range
1149 if(confidence == std::numeric_limits<double>::infinity()) {
1150 acceleration.confidence.value = AccelerationConfidence::UNAVAILABLE;
1151 } else if (confidence > AccelerationConfidence::MAX || confidence < AccelerationConfidence::MIN) {
1152 acceleration.confidence.value = AccelerationConfidence::OUT_OF_RANGE;
1153 } else {
1154 acceleration.confidence.value = static_cast<uint8_t>(confidence);
1155 }
1156}
1157
1170inline void setAccelerationOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_acceleration,
1171 const double x_std = std::numeric_limits<double>::infinity(),
1172 const double y_std = std::numeric_limits<double>::infinity(),
1173 const double z_std = std::numeric_limits<double>::infinity()) {
1174 object.acceleration.choice = Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION;
1175 setAccelerationComponent(object.acceleration.cartesian_acceleration.x_acceleration, cartesian_acceleration.x * 10,
1176 x_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1177 setAccelerationComponent(object.acceleration.cartesian_acceleration.y_acceleration, cartesian_acceleration.y * 10,
1178 y_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1179 if (cartesian_acceleration.z != 0.0) {
1180 setAccelerationComponent(object.acceleration.cartesian_acceleration.z_acceleration, cartesian_acceleration.z * 10,
1181 z_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1182 object.acceleration.cartesian_acceleration.z_acceleration_is_present = true;
1183 }
1184 object.acceleration_is_present = true;
1185}
1186
1197inline void setYawOfPerceivedObject(PerceivedObject& object, const double yaw,
1198 double yaw_std = std::numeric_limits<double>::infinity()) {
1199 // wrap angle to range [0, 360)
1200 double yaw_in_degrees = yaw * 180 / M_PI;
1201 while (yaw_in_degrees >= 360.0) yaw_in_degrees -= 360.0;
1202 while (yaw_in_degrees < 0.0) yaw_in_degrees += 360.0;
1203 object.angles.z_angle.value.value = yaw_in_degrees * 10;
1204
1205 if(yaw_std == std::numeric_limits<double>::infinity()) {
1206 object.angles.z_angle.confidence.value = AngleConfidence::UNAVAILABLE;
1207 } else {
1208 yaw_std *= 180.0 / M_PI;
1209 yaw_std *= 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to 0.1 degrees
1210
1211 if (yaw_std > AngleConfidence::MAX || yaw_std < AngleConfidence::MIN) {
1212 object.angles.z_angle.confidence.value = AngleConfidence::OUT_OF_RANGE;
1213 } else {
1214 object.angles.z_angle.confidence.value = static_cast<uint8_t>(yaw_std);
1215 }
1216 }
1217 object.angles_is_present = true;
1218}
1219
1231inline void setYawRateOfPerceivedObject(PerceivedObject& object, const double yaw_rate,
1232 double yaw_rate_std = std::numeric_limits<double>::infinity()) {
1233 double yaw_rate_in_degrees = yaw_rate * 180.0 / M_PI;
1234 // limit value range
1235 if (yaw_rate_in_degrees < CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE) {
1236 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE;
1237 } else if (yaw_rate_in_degrees > CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1238 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1239 }
1240
1241 object.z_angular_velocity.value.value = yaw_rate_in_degrees;
1242
1243 if(yaw_rate_std == std::numeric_limits<double>::infinity()) {
1244 object.z_angular_velocity.confidence.value = AngularSpeedConfidence::UNAVAILABLE;
1245 } else {
1246 yaw_rate_std *= 180.0 / M_PI;
1247 yaw_rate_std *= etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to degrees/s
1248 // How stupid is this?!
1249 static const std::map<double, uint8_t> confidence_map = {
1250 {1.0, AngularSpeedConfidence::DEG_SEC_01},
1251 {2.0, AngularSpeedConfidence::DEG_SEC_02},
1252 {5.0, AngularSpeedConfidence::DEG_SEC_05},
1253 {10.0, AngularSpeedConfidence::DEG_SEC_10},
1254 {20.0, AngularSpeedConfidence::DEG_SEC_20},
1255 {50.0, AngularSpeedConfidence::DEG_SEC_50},
1256 {std::numeric_limits<double>::infinity(), AngularSpeedConfidence::OUT_OF_RANGE},
1257 };
1258 for(const auto& [thresh, conf_val] : confidence_map) {
1259 if (yaw_rate_std <= thresh) {
1260 object.z_angular_velocity.confidence.value = conf_val;
1261 break;
1262 }
1263 }
1264 }
1265
1266 object.z_angular_velocity_is_present = true;
1267}
1268
1283inline void setObjectDimension(ObjectDimension& dimension, const double value,
1284 const double confidence = std::numeric_limits<double>::infinity()) {
1285 // limit value range
1286 if (value < ObjectDimensionValue::MIN || value > ObjectDimensionValue::MAX) {
1287 dimension.value.value = ObjectDimensionValue::OUT_OF_RANGE;
1288 } else {
1289 dimension.value.value = static_cast<uint16_t>(value);
1290 }
1291
1292 // limit confidence range
1293 if (confidence == std::numeric_limits<double>::infinity()) {
1294 dimension.confidence.value = ObjectDimensionConfidence::UNAVAILABLE;
1295 } else if (confidence > ObjectDimensionConfidence::MAX || confidence < ObjectDimensionConfidence::MIN) {
1296 dimension.confidence.value = ObjectDimensionConfidence::OUT_OF_RANGE;
1297 } else {
1298 dimension.confidence.value = static_cast<uint8_t>(confidence);
1299 }
1300
1301}
1302
1313inline void setXDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1314 const double std = std::numeric_limits<double>::infinity()) {
1315 setObjectDimension(object.object_dimension_x, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1316 object.object_dimension_x_is_present = true;
1317}
1318
1329inline void setYDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1330 const double std = std::numeric_limits<double>::infinity()) {
1331 setObjectDimension(object.object_dimension_y, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1332 object.object_dimension_y_is_present = true;
1333}
1334
1345inline void setZDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1346 const double std = std::numeric_limits<double>::infinity()) {
1347 setObjectDimension(object.object_dimension_z, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1348 object.object_dimension_z_is_present = true;
1349}
1350
1362inline void setDimensionsOfPerceivedObject(PerceivedObject& object, const gm::Vector3& dimensions,
1363 const double x_std = std::numeric_limits<double>::infinity(),
1364 const double y_std = std::numeric_limits<double>::infinity(),
1365 const double z_std = std::numeric_limits<double>::infinity()) {
1366 setXDimensionOfPerceivedObject(object, dimensions.x, x_std);
1367 setYDimensionOfPerceivedObject(object, dimensions.y, y_std);
1368 setZDimensionOfPerceivedObject(object, dimensions.z, z_std);
1369}
1370
1380inline void initPerceivedObject(PerceivedObject& object, const gm::Point& point, const int16_t delta_time = 0) {
1381 setPositionOfPerceivedObject(object, point);
1382 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1383}
1384
1397inline void initPerceivedObjectWithUTMPosition(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1398 const gm::PointStamped& point, const int16_t delta_time = 0) {
1399 setUTMPositionOfPerceivedObject(cpm, object, point);
1400 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1401}
1402
1412inline void initPerceivedObjectContainer(WrappedCpmContainer& container, const uint8_t n_objects = 0) {
1413 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER;
1414 container.container_data_perceived_object_container.number_of_perceived_objects.value = n_objects;
1415}
1416
1430inline void addPerceivedObjectToContainer(WrappedCpmContainer& container, const PerceivedObject& perceived_object) {
1431 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER) {
1432 container.container_data_perceived_object_container.perceived_objects.array.push_back(perceived_object);
1433 container.container_data_perceived_object_container.number_of_perceived_objects.value =
1434 container.container_data_perceived_object_container.perceived_objects.array.size();
1435 } else {
1436 throw std::invalid_argument("Container is not a PerceivedObjectContainer");
1437 }
1438}
1439
1452inline void addContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1453 // check for maximum number of containers
1454 if (cpm.payload.cpm_containers.value.array.size() < WrappedCpmContainers::MAX_SIZE) {
1455 cpm.payload.cpm_containers.value.array.push_back(container);
1456 } else {
1457 throw std::invalid_argument("Maximum number of CPM-Containers reached");
1458 }
1459}
1460
1469inline void setWGSRefPosConfidence(CollectivePerceptionMessage& cpm, const std::array<double, 4>& covariance_matrix) {
1470 setWGSPosConfidenceEllipse(cpm.payload.management_container.reference_position.position_confidence_ellipse,
1471 covariance_matrix);
1472}
1473
1482inline void initSensorInformationContainer(WrappedCpmContainer& container) {
1483 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER;
1484 container.container_data_sensor_information_container.array = std::vector<SensorInformation>();
1485}
1486
1497inline void setSensorID(SensorInformation& sensor_information, const uint8_t sensor_id = 0) {
1498 throwIfOutOfRange(sensor_id, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1499 sensor_information.sensor_id.value = sensor_id;
1500}
1501
1512inline void setSensorType(SensorInformation& sensor_information, const uint8_t sensor_type = SensorType::UNDEFINED) {
1513 throwIfOutOfRange(sensor_type, SensorType::MIN, SensorType::MAX, "SensorType");
1514 sensor_information.sensor_type.value = sensor_type;
1515}
1516
1535inline void addSensorInformationToContainer(WrappedCpmContainer& container, const SensorInformation& sensor_information) {
1536 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1537 // check for maximum number of SensorInformation entries
1538 if (container.container_data_sensor_information_container.array.size() < SensorInformationContainer::MAX_SIZE ) {
1539 throwIfOutOfRange(sensor_information.sensor_id.value, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1540 throwIfOutOfRange(sensor_information.sensor_type.value, SensorType::MIN, SensorType::MAX, "SensorType");
1541 container.container_data_sensor_information_container.array.push_back(sensor_information);
1542 } else {
1543 throw std::invalid_argument("Maximum number of entries SensorInformationContainers reached");
1544 }
1545 } else {
1546 throw std::invalid_argument("Container is not a SensorInformationContainer");
1547 }
1548}
1549
1564inline void addSensorInformationContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1565 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1566 throwIfOutOfRange(container.container_data_sensor_information_container.array.size(),
1567 SensorInformationContainer::MIN_SIZE, SensorInformationContainer::MAX_SIZE, "SensorInformationContainer array size"
1568 );
1569 addContainerToCPM(cpm, container);
1570 } else {
1571 throw std::invalid_argument("Container is not a SensorInformationContainer");
1572 }
1573}
1574
1575} // namespace etsi_its_cpm_ts_msgs::access

◆ setSensorType()

void etsi_its_cpm_ts_msgs::access::setSensorType ( SensorInformation & sensor_information,
const uint8_t sensor_type = SensorType::UNDEFINED )
inline

Sets the sensorType of a SensorInformation object.

This function sets the sensorType of a SensorInformation object. The sensorType is limited to the range defined by SensorType::MIN and SensorType::MAX.

Parameters
sensor_informationThe SensorInformation object to set the sensorType for.
sensor_typeThe sensorType to set (default: SensorType::UNDEFINED).
Exceptions
std::invalid_argumentif the sensor_type is out of range.

Definition at line 850 of file cpm_ts_setters.h.

886 {
887
889
899inline void setItsPduHeader(CollectivePerceptionMessage& cpm, const uint32_t station_id,
900 const uint8_t protocol_version = 0) {
901 setItsPduHeader(cpm.header, MessageId::CPM, station_id, protocol_version);
902}
903
915inline void setReferenceTime(
916 CollectivePerceptionMessage& cpm, const uint64_t unix_nanosecs,
917 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
918 TimestampIts t_its;
919 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
920 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
921 cpm.payload.management_container.reference_time = t_its;
922}
923
935inline void setReferencePosition(CollectivePerceptionMessage& cpm, const double latitude, const double longitude,
936 const double altitude = AltitudeValue::UNAVAILABLE) {
937 setReferencePosition(cpm.payload.management_container.reference_position, latitude, longitude, altitude);
938}
939
952inline void setFromUTMPosition(CollectivePerceptionMessage& cpm, const gm::PointStamped& utm_position, const int& zone,
953 const bool& northp) {
954 setFromUTMPosition(cpm.payload.management_container.reference_position, utm_position, zone, northp);
955}
956
965inline void setIdOfPerceivedObject(PerceivedObject& object, const uint16_t id) {
966 object.object_id.value = id;
967 object.object_id_is_present = true;
968}
969
981inline void setMeasurementDeltaTimeOfPerceivedObject(PerceivedObject& object, const int16_t delta_time = 0) {
982 if (delta_time < DeltaTimeMilliSecondSigned::MIN || delta_time > DeltaTimeMilliSecondSigned::MAX) {
983 throw std::invalid_argument("MeasurementDeltaTime out of range");
984 } else {
985 object.measurement_delta_time.value = delta_time;
986 }
987}
988
1002inline void setCartesianCoordinateWithConfidence(CartesianCoordinateWithConfidence& coordinate, const double value,
1003 const double confidence = std::numeric_limits<double>::infinity()) {
1004 // limit value range
1005 if (value < CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE) {
1006 coordinate.value.value = CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE;
1007 } else if (value > CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE) {
1008 coordinate.value.value = CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE;
1009 } else {
1010 coordinate.value.value = static_cast<int32_t>(value);
1011 }
1012
1013 // limit confidence range
1014 if (confidence == std::numeric_limits<double>::infinity()) {
1015 coordinate.confidence.value = CoordinateConfidence::UNAVAILABLE;
1016 } else if (confidence > CoordinateConfidence::MAX || confidence < CoordinateConfidence::MIN) {
1017 coordinate.confidence.value = CoordinateConfidence::OUT_OF_RANGE;
1018 } else {
1019 coordinate.confidence.value = static_cast<uint16_t>(confidence);
1020 }
1021}
1022
1034inline void setPositionOfPerceivedObject(PerceivedObject& object, const gm::Point& point,
1035 const double x_std = std::numeric_limits<double>::infinity(),
1036 const double y_std = std::numeric_limits<double>::infinity(),
1037 const double z_std = std::numeric_limits<double>::infinity()) {
1038 setCartesianCoordinateWithConfidence(object.position.x_coordinate, point.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1039 setCartesianCoordinateWithConfidence(object.position.y_coordinate, point.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1040 if (point.z != 0.0) {
1041 setCartesianCoordinateWithConfidence(object.position.z_coordinate, point.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1042 object.position.z_coordinate_is_present = true;
1043 }
1044}
1045
1061inline void setUTMPositionOfPerceivedObject(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1062 const gm::PointStamped& utm_position,
1063 const double x_std = std::numeric_limits<double>::infinity(),
1064 const double y_std = std::numeric_limits<double>::infinity(),
1065 const double z_std = std::numeric_limits<double>::infinity()) {
1066 gm::PointStamped reference_position = getUTMPosition(cpm);
1067 if (utm_position.header.frame_id != reference_position.header.frame_id) {
1068 throw std::invalid_argument("UTM-Position frame_id (" + utm_position.header.frame_id +
1069 ") does not match the reference position frame_id (" + reference_position.header.frame_id +
1070 ")");
1071 }
1072 setCartesianCoordinateWithConfidence(object.position.x_coordinate,
1073 (utm_position.point.x - reference_position.point.x) * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1074 setCartesianCoordinateWithConfidence(object.position.y_coordinate,
1075 (utm_position.point.y - reference_position.point.y) * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1076 if (utm_position.point.z != 0.0) {
1077 setCartesianCoordinateWithConfidence(object.position.z_coordinate,
1078 (utm_position.point.z - reference_position.point.z) * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1079 object.position.z_coordinate_is_present = true;
1080 }
1081}
1082
1094inline void setVelocityComponent(VelocityComponent& velocity, const double value,
1095 const double confidence = std::numeric_limits<double>::infinity()) {
1096 // limit value range
1097 if (value < VelocityComponentValue::NEGATIVE_OUT_OF_RANGE) {
1098 velocity.value.value = VelocityComponentValue::NEGATIVE_OUT_OF_RANGE;
1099 } else if (value > VelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1100 velocity.value.value = VelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1101 } else {
1102 velocity.value.value = static_cast<int16_t>(value);
1103 }
1104
1105 // limit confidence range
1106 if(confidence == std::numeric_limits<double>::infinity()) {
1107 velocity.confidence.value = SpeedConfidence::UNAVAILABLE;
1108 } else if (confidence > SpeedConfidence::MAX || confidence < SpeedConfidence::MIN) {
1109 velocity.confidence.value = SpeedConfidence::OUT_OF_RANGE;
1110 } else {
1111 velocity.confidence.value = static_cast<uint8_t>(confidence);
1112 }
1113}
1114
1127inline void setVelocityOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_velocity,
1128 const double x_std = std::numeric_limits<double>::infinity(),
1129 const double y_std = std::numeric_limits<double>::infinity(),
1130 const double z_std = std::numeric_limits<double>::infinity()) {
1131 object.velocity.choice = Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY;
1132 setVelocityComponent(object.velocity.cartesian_velocity.x_velocity, cartesian_velocity.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1133 setVelocityComponent(object.velocity.cartesian_velocity.y_velocity, cartesian_velocity.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1134 if (cartesian_velocity.z != 0.0) {
1135 setVelocityComponent(object.velocity.cartesian_velocity.z_velocity, cartesian_velocity.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1136 object.velocity.cartesian_velocity.z_velocity_is_present = true;
1137 }
1138 object.velocity_is_present = true;
1139}
1140
1152inline void setAccelerationComponent(AccelerationComponent& acceleration, const double value,
1153 const double confidence = std::numeric_limits<double>::infinity()) {
1154 // limit value range
1155 if (value < AccelerationValue::NEGATIVE_OUT_OF_RANGE) {
1156 acceleration.value.value = AccelerationValue::NEGATIVE_OUT_OF_RANGE;
1157 } else if (value > AccelerationValue::POSITIVE_OUT_OF_RANGE) {
1158 acceleration.value.value = AccelerationValue::POSITIVE_OUT_OF_RANGE;
1159 } else {
1160 acceleration.value.value = static_cast<int16_t>(value);
1161 }
1162
1163 // limit confidence range
1164 if(confidence == std::numeric_limits<double>::infinity()) {
1165 acceleration.confidence.value = AccelerationConfidence::UNAVAILABLE;
1166 } else if (confidence > AccelerationConfidence::MAX || confidence < AccelerationConfidence::MIN) {
1167 acceleration.confidence.value = AccelerationConfidence::OUT_OF_RANGE;
1168 } else {
1169 acceleration.confidence.value = static_cast<uint8_t>(confidence);
1170 }
1171}
1172
1185inline void setAccelerationOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_acceleration,
1186 const double x_std = std::numeric_limits<double>::infinity(),
1187 const double y_std = std::numeric_limits<double>::infinity(),
1188 const double z_std = std::numeric_limits<double>::infinity()) {
1189 object.acceleration.choice = Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION;
1190 setAccelerationComponent(object.acceleration.cartesian_acceleration.x_acceleration, cartesian_acceleration.x * 10,
1191 x_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1192 setAccelerationComponent(object.acceleration.cartesian_acceleration.y_acceleration, cartesian_acceleration.y * 10,
1193 y_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1194 if (cartesian_acceleration.z != 0.0) {
1195 setAccelerationComponent(object.acceleration.cartesian_acceleration.z_acceleration, cartesian_acceleration.z * 10,
1196 z_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1197 object.acceleration.cartesian_acceleration.z_acceleration_is_present = true;
1198 }
1199 object.acceleration_is_present = true;
1200}
1201
1212inline void setYawOfPerceivedObject(PerceivedObject& object, const double yaw,
1213 double yaw_std = std::numeric_limits<double>::infinity()) {
1214 // wrap angle to range [0, 360)
1215 double yaw_in_degrees = yaw * 180 / M_PI;
1216 while (yaw_in_degrees >= 360.0) yaw_in_degrees -= 360.0;
1217 while (yaw_in_degrees < 0.0) yaw_in_degrees += 360.0;
1218 object.angles.z_angle.value.value = yaw_in_degrees * 10;
1219
1220 if(yaw_std == std::numeric_limits<double>::infinity()) {
1221 object.angles.z_angle.confidence.value = AngleConfidence::UNAVAILABLE;
1222 } else {
1223 yaw_std *= 180.0 / M_PI;
1224 yaw_std *= 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to 0.1 degrees
1225
1226 if (yaw_std > AngleConfidence::MAX || yaw_std < AngleConfidence::MIN) {
1227 object.angles.z_angle.confidence.value = AngleConfidence::OUT_OF_RANGE;
1228 } else {
1229 object.angles.z_angle.confidence.value = static_cast<uint8_t>(yaw_std);
1230 }
1231 }
1232 object.angles_is_present = true;
1233}
1234
1246inline void setYawRateOfPerceivedObject(PerceivedObject& object, const double yaw_rate,
1247 double yaw_rate_std = std::numeric_limits<double>::infinity()) {
1248 double yaw_rate_in_degrees = yaw_rate * 180.0 / M_PI;
1249 // limit value range
1250 if (yaw_rate_in_degrees < CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE) {
1251 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE;
1252 } else if (yaw_rate_in_degrees > CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1253 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1254 }
1255
1256 object.z_angular_velocity.value.value = yaw_rate_in_degrees;
1257
1258 if(yaw_rate_std == std::numeric_limits<double>::infinity()) {
1259 object.z_angular_velocity.confidence.value = AngularSpeedConfidence::UNAVAILABLE;
1260 } else {
1261 yaw_rate_std *= 180.0 / M_PI;
1262 yaw_rate_std *= etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to degrees/s
1263 // How stupid is this?!
1264 static const std::map<double, uint8_t> confidence_map = {
1265 {1.0, AngularSpeedConfidence::DEG_SEC_01},
1266 {2.0, AngularSpeedConfidence::DEG_SEC_02},
1267 {5.0, AngularSpeedConfidence::DEG_SEC_05},
1268 {10.0, AngularSpeedConfidence::DEG_SEC_10},
1269 {20.0, AngularSpeedConfidence::DEG_SEC_20},
1270 {50.0, AngularSpeedConfidence::DEG_SEC_50},
1271 {std::numeric_limits<double>::infinity(), AngularSpeedConfidence::OUT_OF_RANGE},
1272 };
1273 for(const auto& [thresh, conf_val] : confidence_map) {
1274 if (yaw_rate_std <= thresh) {
1275 object.z_angular_velocity.confidence.value = conf_val;
1276 break;
1277 }
1278 }
1279 }
1280
1281 object.z_angular_velocity_is_present = true;
1282}
1283
1298inline void setObjectDimension(ObjectDimension& dimension, const double value,
1299 const double confidence = std::numeric_limits<double>::infinity()) {
1300 // limit value range
1301 if (value < ObjectDimensionValue::MIN || value > ObjectDimensionValue::MAX) {
1302 dimension.value.value = ObjectDimensionValue::OUT_OF_RANGE;
1303 } else {
1304 dimension.value.value = static_cast<uint16_t>(value);
1305 }
1306
1307 // limit confidence range
1308 if (confidence == std::numeric_limits<double>::infinity()) {
1309 dimension.confidence.value = ObjectDimensionConfidence::UNAVAILABLE;
1310 } else if (confidence > ObjectDimensionConfidence::MAX || confidence < ObjectDimensionConfidence::MIN) {
1311 dimension.confidence.value = ObjectDimensionConfidence::OUT_OF_RANGE;
1312 } else {
1313 dimension.confidence.value = static_cast<uint8_t>(confidence);
1314 }
1315
1316}
1317
1328inline void setXDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1329 const double std = std::numeric_limits<double>::infinity()) {
1330 setObjectDimension(object.object_dimension_x, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1331 object.object_dimension_x_is_present = true;
1332}
1333
1344inline void setYDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1345 const double std = std::numeric_limits<double>::infinity()) {
1346 setObjectDimension(object.object_dimension_y, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1347 object.object_dimension_y_is_present = true;
1348}
1349
1360inline void setZDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1361 const double std = std::numeric_limits<double>::infinity()) {
1362 setObjectDimension(object.object_dimension_z, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1363 object.object_dimension_z_is_present = true;
1364}
1365
1377inline void setDimensionsOfPerceivedObject(PerceivedObject& object, const gm::Vector3& dimensions,
1378 const double x_std = std::numeric_limits<double>::infinity(),
1379 const double y_std = std::numeric_limits<double>::infinity(),
1380 const double z_std = std::numeric_limits<double>::infinity()) {
1381 setXDimensionOfPerceivedObject(object, dimensions.x, x_std);
1382 setYDimensionOfPerceivedObject(object, dimensions.y, y_std);
1383 setZDimensionOfPerceivedObject(object, dimensions.z, z_std);
1384}
1385
1395inline void initPerceivedObject(PerceivedObject& object, const gm::Point& point, const int16_t delta_time = 0) {
1396 setPositionOfPerceivedObject(object, point);
1397 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1398}
1399
1412inline void initPerceivedObjectWithUTMPosition(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1413 const gm::PointStamped& point, const int16_t delta_time = 0) {
1414 setUTMPositionOfPerceivedObject(cpm, object, point);
1415 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1416}
1417
1427inline void initPerceivedObjectContainer(WrappedCpmContainer& container, const uint8_t n_objects = 0) {
1428 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER;
1429 container.container_data_perceived_object_container.number_of_perceived_objects.value = n_objects;
1430}
1431
1445inline void addPerceivedObjectToContainer(WrappedCpmContainer& container, const PerceivedObject& perceived_object) {
1446 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER) {
1447 container.container_data_perceived_object_container.perceived_objects.array.push_back(perceived_object);
1448 container.container_data_perceived_object_container.number_of_perceived_objects.value =
1449 container.container_data_perceived_object_container.perceived_objects.array.size();
1450 } else {
1451 throw std::invalid_argument("Container is not a PerceivedObjectContainer");
1452 }
1453}
1454
1467inline void addContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1468 // check for maximum number of containers
1469 if (cpm.payload.cpm_containers.value.array.size() < WrappedCpmContainers::MAX_SIZE) {
1470 cpm.payload.cpm_containers.value.array.push_back(container);
1471 } else {
1472 throw std::invalid_argument("Maximum number of CPM-Containers reached");
1473 }
1474}
1475
1484inline void setWGSRefPosConfidence(CollectivePerceptionMessage& cpm, const std::array<double, 4>& covariance_matrix) {
1485 setWGSPosConfidenceEllipse(cpm.payload.management_container.reference_position.position_confidence_ellipse,
1486 covariance_matrix);
1487}
1488
1497inline void initSensorInformationContainer(WrappedCpmContainer& container) {
1498 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER;
1499 container.container_data_sensor_information_container.array = std::vector<SensorInformation>();
1500}
1501
1512inline void setSensorID(SensorInformation& sensor_information, const uint8_t sensor_id = 0) {
1513 throwIfOutOfRange(sensor_id, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1514 sensor_information.sensor_id.value = sensor_id;
1515}
1516
1527inline void setSensorType(SensorInformation& sensor_information, const uint8_t sensor_type = SensorType::UNDEFINED) {
1528 throwIfOutOfRange(sensor_type, SensorType::MIN, SensorType::MAX, "SensorType");
1529 sensor_information.sensor_type.value = sensor_type;
1530}
1531
1550inline void addSensorInformationToContainer(WrappedCpmContainer& container, const SensorInformation& sensor_information) {
1551 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1552 // check for maximum number of SensorInformation entries
1553 if (container.container_data_sensor_information_container.array.size() < SensorInformationContainer::MAX_SIZE ) {
1554 throwIfOutOfRange(sensor_information.sensor_id.value, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1555 throwIfOutOfRange(sensor_information.sensor_type.value, SensorType::MIN, SensorType::MAX, "SensorType");
1556 container.container_data_sensor_information_container.array.push_back(sensor_information);
1557 } else {
1558 throw std::invalid_argument("Maximum number of entries SensorInformationContainers reached");
1559 }
1560 } else {
1561 throw std::invalid_argument("Container is not a SensorInformationContainer");
1562 }
1563}
1564
1579inline void addSensorInformationContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1580 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1581 throwIfOutOfRange(container.container_data_sensor_information_container.array.size(),
1582 SensorInformationContainer::MIN_SIZE, SensorInformationContainer::MAX_SIZE, "SensorInformationContainer array size"
1583 );
1584 addContainerToCPM(cpm, container);
1585 } else {
1586 throw std::invalid_argument("Container is not a SensorInformationContainer");
1587 }
1588}
1589
1590} // namespace etsi_its_cpm_ts_msgs::access

◆ setSpeed()

void etsi_its_cpm_ts_msgs::access::setSpeed ( Speed & speed,
const double value,
const double confidence = std::numeric_limits<double>::infinity() )
inline

Set the Speed object.

SpeedConfidence is set to UNAVAILABLE

Parameters
speedobject to set
valueSpeed in in m/s as decimal number
confidencestandard deviation in m/s as decimal number (Optional. Default is std::numeric_limits<double>::infinity(), mapping to SpeedConfidence::UNAVAILABLE)

Definition at line 208 of file cpm_ts_setters.h.

208 : CoordinateConfidence::UNAVAILABLE).
209 *
210 * @throws std::invalid_argument if the UTM-Position frame_id does not match the reference position frame_id.
211 */

◆ setSpeedConfidence()

void etsi_its_cpm_ts_msgs::access::setSpeedConfidence ( SpeedConfidence & speed_confidence,
const double value )
inline

Set the Speed Confidence object.

Parameters
speed_confidenceobject to set
valuestandard deviation in m/s as decimal number

Definition at line 189 of file cpm_ts_setters.h.

191 {
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

◆ setSpeedValue()

void etsi_its_cpm_ts_msgs::access::setSpeedValue ( SpeedValue & speed,
const double value )
inline

Set the SpeedValue object.

Parameters
speedobject to set
valueSpeedValue in m/s as decimal number

Definition at line 177 of file cpm_ts_setters.h.

◆ setStationId()

void etsi_its_cpm_ts_msgs::access::setStationId ( StationId & station_id,
const uint32_t id_value )
inline

Set the Station Id object.

Parameters
station_id
id_value

Definition at line 72 of file cpm_ts_setters.h.

◆ setStationType()

void etsi_its_cpm_ts_msgs::access::setStationType ( TrafficParticipantType & station_type,
const uint8_t value )
inline

Set the Station Type.

Parameters
station_type
value

Definition at line 100 of file cpm_ts_setters.h.

◆ setTimestampITS()

void etsi_its_cpm_ts_msgs::access::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 )
inline

Set the TimestampITS object.

Parameters
[in]timestamp_itsTimestampITS object to set the timestamp
[in]unix_nanosecsUnix-Nanoseconds to set the timestamp for
[in]n_leap_secondsNumber of leap-seconds since 2004. (Defaults to the todays number of leap seconds since 2004.)
[in]epoch_offsetUnix-Timestamp in seconds for the 01.01.2004 at 00:00:00

Definition at line 109 of file cpm_ts_setters.h.

◆ setUTMPositionOfPerceivedObject()

void etsi_its_cpm_ts_msgs::access::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() )
inline

Sets the position of a perceived object based on a UTM position.

This function sets the position of a perceived object using the provided UTM position and the CPM's reference position. It also allows specifying confidence values for the x, y, and z coordinates.

Parameters
cpmThe CPM to get the reference position from.
objectThe PerceivedObject to set the position for.
utm_positiongm::PointStamped representing the UTM position of the object including the frame_id (utm_<zone><N/S>).
x_confidenceThe standard deviation in meters for the x coordinate (default: CoordinateConfidence::UNAVAILABLE).
y_confidenceThe standard deviation in meters for the y coordinate (default: CoordinateConfidence::UNAVAILABLE).
z_confidenceThe standard deviation in meters for the z coordinate (default: CoordinateConfidence::UNAVAILABLE).
Exceptions
std::invalid_argumentif the UTM-Position frame_id does not match the reference position frame_id.

Definition at line 384 of file cpm_ts_setters.h.

◆ setVelocityComponent()

void etsi_its_cpm_ts_msgs::access::setVelocityComponent ( VelocityComponent & velocity,
const double value,
const double confidence = std::numeric_limits<double>::infinity() )
inline

Sets the value and confidence of a VelocityComponent.

This function sets the value and confidence of a VelocityComponent object. The value is limited to a specific range, and the confidence is limited to a specific range as well. If the provided value or confidence is out of range, it will be set to the corresponding out-of-range value.

Parameters
velocityThe VelocityComponent object to set the value and confidence for.
valueThe value to set for the VelocityComponent in cm/s.
confidenceThe confidence to set for the VelocityComponent in cm/s. Default value is infinity, mapping to SpeedConfidence::UNAVAILABLE.

Definition at line 417 of file cpm_ts_setters.h.

◆ setVelocityOfPerceivedObject()

void etsi_its_cpm_ts_msgs::access::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() )
inline

Sets the velocity of a perceived object.

This function sets the velocity of a perceived object using the provided Cartesian velocity components. Optionally, confidence values can be specified for each velocity component.

Parameters
objectThe perceived object for which the velocity is being set.
cartesian_velocityThe Cartesian velocity components (x, y, z) of the object (in m/s).
x_stdThe standard deviation in m/s for the x velocity component (default: infinity).
y_stdThe standard deviation in m/s for the y velocity component (default: infinity).
z_stdThe standard deviation in m/s for the z velocity component (default: infinity).

Definition at line 450 of file cpm_ts_setters.h.

◆ setWGSPosConfidenceEllipse()

template<typename PosConfidenceEllipse>
void etsi_its_cpm_ts_msgs::access::setWGSPosConfidenceEllipse ( PosConfidenceEllipse & position_confidence_ellipse,
const std::array< double, 4 > & covariance_matrix )
inline

Set the Pos Confidence Ellipse object.

Parameters
position_confidence_ellipse
covariance_matrixThe four values of the covariance matrix in the order: cov_xx, cov_xy, cov_yx, cov_yy The matrix has to be SPD, otherwise a std::invalid_argument exception is thrown. Its coordinate system is aligned with the WGS axes (x = North, y = East)
object_headingThe heading of the object in rad, with respect to WGS84

Definition at line 448 of file cpm_ts_setters.h.

◆ setWGSPositionConfidenceEllipse()

template<typename PositionConfidenceEllipse>
void etsi_its_cpm_ts_msgs::access::setWGSPositionConfidenceEllipse ( PositionConfidenceEllipse & position_confidence_ellipse,
const std::array< double, 4 > & covariance_matrix )
inline

Set the Position Confidence Ellipse object.

Parameters
position_confidence_ellipse
covariance_matrixThe four values of the covariance matrix in the order: cov_xx, cov_xy, cov_yx, cov_yy The matrix has to be SPD, otherwise a std::invalid_argument exception is thrown. Its coordinate system is aligned with the WGS axes (x = North, y = East)
object_headingThe heading of the object in rad, with respect to WGS84

Definition at line 206 of file cpm_ts_setters.h.

◆ setWGSRefPosConfidence()

void etsi_its_cpm_ts_msgs::access::setWGSRefPosConfidence ( CollectivePerceptionMessage & cpm,
const std::array< double, 4 > & covariance_matrix )
inline

Set the confidence of the reference position.

Parameters
cpmCPM-Message to set the confidence
covariance_matrixThe four values of the covariance matrix in the order: cov_xx, cov_xy, cov_yx, cov_yy The matrix has to be SPD, otherwise a std::invalid_argument exception is thrown. Its coordinate system is WGS84 (x = North, y = East)

Definition at line 807 of file cpm_ts_setters.h.

856inline void setItsPduHeader(CollectivePerceptionMessage& cpm, const uint32_t station_id,
857 const uint8_t protocol_version = 0) {
858 setItsPduHeader(cpm.header, MessageId::CPM, station_id, protocol_version);
859}
860
872inline void setReferenceTime(
873 CollectivePerceptionMessage& cpm, const uint64_t unix_nanosecs,
874 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.rbegin()->second) {
875 TimestampIts t_its;
876 setTimestampITS(t_its, unix_nanosecs, n_leap_seconds);
877 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
878 cpm.payload.management_container.reference_time = t_its;
879}
880
892inline void setReferencePosition(CollectivePerceptionMessage& cpm, const double latitude, const double longitude,
893 const double altitude = AltitudeValue::UNAVAILABLE) {
894 setReferencePosition(cpm.payload.management_container.reference_position, latitude, longitude, altitude);
895}
896
909inline void setFromUTMPosition(CollectivePerceptionMessage& cpm, const gm::PointStamped& utm_position, const int& zone,
910 const bool& northp) {
911 setFromUTMPosition(cpm.payload.management_container.reference_position, utm_position, zone, northp);
912}
913
922inline void setIdOfPerceivedObject(PerceivedObject& object, const uint16_t id) {
923 object.object_id.value = id;
924 object.object_id_is_present = true;
925}
926
938inline void setMeasurementDeltaTimeOfPerceivedObject(PerceivedObject& object, const int16_t delta_time = 0) {
939 if (delta_time < DeltaTimeMilliSecondSigned::MIN || delta_time > DeltaTimeMilliSecondSigned::MAX) {
940 throw std::invalid_argument("MeasurementDeltaTime out of range");
941 } else {
942 object.measurement_delta_time.value = delta_time;
943 }
944}
945
959inline void setCartesianCoordinateWithConfidence(CartesianCoordinateWithConfidence& coordinate, const double value,
960 const double confidence = std::numeric_limits<double>::infinity()) {
961 // limit value range
962 if (value < CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE) {
963 coordinate.value.value = CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE;
964 } else if (value > CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE) {
965 coordinate.value.value = CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE;
966 } else {
967 coordinate.value.value = static_cast<int32_t>(value);
968 }
969
970 // limit confidence range
971 if (confidence == std::numeric_limits<double>::infinity()) {
972 coordinate.confidence.value = CoordinateConfidence::UNAVAILABLE;
973 } else if (confidence > CoordinateConfidence::MAX || confidence < CoordinateConfidence::MIN) {
974 coordinate.confidence.value = CoordinateConfidence::OUT_OF_RANGE;
975 } else {
976 coordinate.confidence.value = static_cast<uint16_t>(confidence);
977 }
978}
979
991inline void setPositionOfPerceivedObject(PerceivedObject& object, const gm::Point& point,
992 const double x_std = std::numeric_limits<double>::infinity(),
993 const double y_std = std::numeric_limits<double>::infinity(),
994 const double z_std = std::numeric_limits<double>::infinity()) {
995 setCartesianCoordinateWithConfidence(object.position.x_coordinate, point.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
996 setCartesianCoordinateWithConfidence(object.position.y_coordinate, point.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
997 if (point.z != 0.0) {
998 setCartesianCoordinateWithConfidence(object.position.z_coordinate, point.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
999 object.position.z_coordinate_is_present = true;
1000 }
1001}
1002
1018inline void setUTMPositionOfPerceivedObject(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1019 const gm::PointStamped& utm_position,
1020 const double x_std = std::numeric_limits<double>::infinity(),
1021 const double y_std = std::numeric_limits<double>::infinity(),
1022 const double z_std = std::numeric_limits<double>::infinity()) {
1023 gm::PointStamped reference_position = getUTMPosition(cpm);
1024 if (utm_position.header.frame_id != reference_position.header.frame_id) {
1025 throw std::invalid_argument("UTM-Position frame_id (" + utm_position.header.frame_id +
1026 ") does not match the reference position frame_id (" + reference_position.header.frame_id +
1027 ")");
1028 }
1029 setCartesianCoordinateWithConfidence(object.position.x_coordinate,
1030 (utm_position.point.x - reference_position.point.x) * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1031 setCartesianCoordinateWithConfidence(object.position.y_coordinate,
1032 (utm_position.point.y - reference_position.point.y) * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1033 if (utm_position.point.z != 0.0) {
1034 setCartesianCoordinateWithConfidence(object.position.z_coordinate,
1035 (utm_position.point.z - reference_position.point.z) * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1036 object.position.z_coordinate_is_present = true;
1037 }
1038}
1039
1051inline void setVelocityComponent(VelocityComponent& velocity, const double value,
1052 const double confidence = std::numeric_limits<double>::infinity()) {
1053 // limit value range
1054 if (value < VelocityComponentValue::NEGATIVE_OUT_OF_RANGE) {
1055 velocity.value.value = VelocityComponentValue::NEGATIVE_OUT_OF_RANGE;
1056 } else if (value > VelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1057 velocity.value.value = VelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1058 } else {
1059 velocity.value.value = static_cast<int16_t>(value);
1060 }
1061
1062 // limit confidence range
1063 if(confidence == std::numeric_limits<double>::infinity()) {
1064 velocity.confidence.value = SpeedConfidence::UNAVAILABLE;
1065 } else if (confidence > SpeedConfidence::MAX || confidence < SpeedConfidence::MIN) {
1066 velocity.confidence.value = SpeedConfidence::OUT_OF_RANGE;
1067 } else {
1068 velocity.confidence.value = static_cast<uint8_t>(confidence);
1069 }
1070}
1071
1084inline void setVelocityOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_velocity,
1085 const double x_std = std::numeric_limits<double>::infinity(),
1086 const double y_std = std::numeric_limits<double>::infinity(),
1087 const double z_std = std::numeric_limits<double>::infinity()) {
1088 object.velocity.choice = Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY;
1089 setVelocityComponent(object.velocity.cartesian_velocity.x_velocity, cartesian_velocity.x * 100, x_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1090 setVelocityComponent(object.velocity.cartesian_velocity.y_velocity, cartesian_velocity.y * 100, y_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1091 if (cartesian_velocity.z != 0.0) {
1092 setVelocityComponent(object.velocity.cartesian_velocity.z_velocity, cartesian_velocity.z * 100, z_std * 100 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1093 object.velocity.cartesian_velocity.z_velocity_is_present = true;
1094 }
1095 object.velocity_is_present = true;
1096}
1097
1109inline void setAccelerationComponent(AccelerationComponent& acceleration, const double value,
1110 const double confidence = std::numeric_limits<double>::infinity()) {
1111 // limit value range
1112 if (value < AccelerationValue::NEGATIVE_OUT_OF_RANGE) {
1113 acceleration.value.value = AccelerationValue::NEGATIVE_OUT_OF_RANGE;
1114 } else if (value > AccelerationValue::POSITIVE_OUT_OF_RANGE) {
1115 acceleration.value.value = AccelerationValue::POSITIVE_OUT_OF_RANGE;
1116 } else {
1117 acceleration.value.value = static_cast<int16_t>(value);
1118 }
1119
1120 // limit confidence range
1121 if(confidence == std::numeric_limits<double>::infinity()) {
1122 acceleration.confidence.value = AccelerationConfidence::UNAVAILABLE;
1123 } else if (confidence > AccelerationConfidence::MAX || confidence < AccelerationConfidence::MIN) {
1124 acceleration.confidence.value = AccelerationConfidence::OUT_OF_RANGE;
1125 } else {
1126 acceleration.confidence.value = static_cast<uint8_t>(confidence);
1127 }
1128}
1129
1142inline void setAccelerationOfPerceivedObject(PerceivedObject& object, const gm::Vector3& cartesian_acceleration,
1143 const double x_std = std::numeric_limits<double>::infinity(),
1144 const double y_std = std::numeric_limits<double>::infinity(),
1145 const double z_std = std::numeric_limits<double>::infinity()) {
1146 object.acceleration.choice = Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION;
1147 setAccelerationComponent(object.acceleration.cartesian_acceleration.x_acceleration, cartesian_acceleration.x * 10,
1148 x_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1149 setAccelerationComponent(object.acceleration.cartesian_acceleration.y_acceleration, cartesian_acceleration.y * 10,
1150 y_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1151 if (cartesian_acceleration.z != 0.0) {
1152 setAccelerationComponent(object.acceleration.cartesian_acceleration.z_acceleration, cartesian_acceleration.z * 10,
1153 z_std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1154 object.acceleration.cartesian_acceleration.z_acceleration_is_present = true;
1155 }
1156 object.acceleration_is_present = true;
1157}
1158
1169inline void setYawOfPerceivedObject(PerceivedObject& object, const double yaw,
1170 double yaw_std = std::numeric_limits<double>::infinity()) {
1171 // wrap angle to range [0, 360)
1172 double yaw_in_degrees = yaw * 180 / M_PI;
1173 while (yaw_in_degrees >= 360.0) yaw_in_degrees -= 360.0;
1174 while (yaw_in_degrees < 0.0) yaw_in_degrees += 360.0;
1175 object.angles.z_angle.value.value = yaw_in_degrees * 10;
1176
1177 if(yaw_std == std::numeric_limits<double>::infinity()) {
1178 object.angles.z_angle.confidence.value = AngleConfidence::UNAVAILABLE;
1179 } else {
1180 yaw_std *= 180.0 / M_PI;
1181 yaw_std *= 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to 0.1 degrees
1182
1183 if (yaw_std > AngleConfidence::MAX || yaw_std < AngleConfidence::MIN) {
1184 object.angles.z_angle.confidence.value = AngleConfidence::OUT_OF_RANGE;
1185 } else {
1186 object.angles.z_angle.confidence.value = static_cast<uint8_t>(yaw_std);
1187 }
1188 }
1189 object.angles_is_present = true;
1190}
1191
1203inline void setYawRateOfPerceivedObject(PerceivedObject& object, const double yaw_rate,
1204 double yaw_rate_std = std::numeric_limits<double>::infinity()) {
1205 double yaw_rate_in_degrees = yaw_rate * 180.0 / M_PI;
1206 // limit value range
1207 if (yaw_rate_in_degrees < CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE) {
1208 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE;
1209 } else if (yaw_rate_in_degrees > CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1210 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1211 }
1212
1213 object.z_angular_velocity.value.value = yaw_rate_in_degrees;
1214
1215 if(yaw_rate_std == std::numeric_limits<double>::infinity()) {
1216 object.z_angular_velocity.confidence.value = AngularSpeedConfidence::UNAVAILABLE;
1217 } else {
1218 yaw_rate_std *= 180.0 / M_PI;
1219 yaw_rate_std *= etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR; // convert to degrees/s
1220 // How stupid is this?!
1221 static const std::map<double, uint8_t> confidence_map = {
1222 {1.0, AngularSpeedConfidence::DEG_SEC_01},
1223 {2.0, AngularSpeedConfidence::DEG_SEC_02},
1224 {5.0, AngularSpeedConfidence::DEG_SEC_05},
1225 {10.0, AngularSpeedConfidence::DEG_SEC_10},
1226 {20.0, AngularSpeedConfidence::DEG_SEC_20},
1227 {50.0, AngularSpeedConfidence::DEG_SEC_50},
1228 {std::numeric_limits<double>::infinity(), AngularSpeedConfidence::OUT_OF_RANGE},
1229 };
1230 for(const auto& [thresh, conf_val] : confidence_map) {
1231 if (yaw_rate_std <= thresh) {
1232 object.z_angular_velocity.confidence.value = conf_val;
1233 break;
1234 }
1235 }
1236 }
1237
1238 object.z_angular_velocity_is_present = true;
1239}
1240
1255inline void setObjectDimension(ObjectDimension& dimension, const double value,
1256 const double confidence = std::numeric_limits<double>::infinity()) {
1257 // limit value range
1258 if (value < ObjectDimensionValue::MIN || value > ObjectDimensionValue::MAX) {
1259 dimension.value.value = ObjectDimensionValue::OUT_OF_RANGE;
1260 } else {
1261 dimension.value.value = static_cast<uint16_t>(value);
1262 }
1263
1264 // limit confidence range
1265 if (confidence == std::numeric_limits<double>::infinity()) {
1266 dimension.confidence.value = ObjectDimensionConfidence::UNAVAILABLE;
1267 } else if (confidence > ObjectDimensionConfidence::MAX || confidence < ObjectDimensionConfidence::MIN) {
1268 dimension.confidence.value = ObjectDimensionConfidence::OUT_OF_RANGE;
1269 } else {
1270 dimension.confidence.value = static_cast<uint8_t>(confidence);
1271 }
1272
1273}
1274
1285inline void setXDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1286 const double std = std::numeric_limits<double>::infinity()) {
1287 setObjectDimension(object.object_dimension_x, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1288 object.object_dimension_x_is_present = true;
1289}
1290
1301inline void setYDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1302 const double std = std::numeric_limits<double>::infinity()) {
1303 setObjectDimension(object.object_dimension_y, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1304 object.object_dimension_y_is_present = true;
1305}
1306
1317inline void setZDimensionOfPerceivedObject(PerceivedObject& object, const double value,
1318 const double std = std::numeric_limits<double>::infinity()) {
1319 setObjectDimension(object.object_dimension_z, value * 10, std * 10 * etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR);
1320 object.object_dimension_z_is_present = true;
1321}
1322
1334inline void setDimensionsOfPerceivedObject(PerceivedObject& object, const gm::Vector3& dimensions,
1335 const double x_std = std::numeric_limits<double>::infinity(),
1336 const double y_std = std::numeric_limits<double>::infinity(),
1337 const double z_std = std::numeric_limits<double>::infinity()) {
1338 setXDimensionOfPerceivedObject(object, dimensions.x, x_std);
1339 setYDimensionOfPerceivedObject(object, dimensions.y, y_std);
1340 setZDimensionOfPerceivedObject(object, dimensions.z, z_std);
1341}
1342
1352inline void initPerceivedObject(PerceivedObject& object, const gm::Point& point, const int16_t delta_time = 0) {
1353 setPositionOfPerceivedObject(object, point);
1354 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1355}
1356
1369inline void initPerceivedObjectWithUTMPosition(CollectivePerceptionMessage& cpm, PerceivedObject& object,
1370 const gm::PointStamped& point, const int16_t delta_time = 0) {
1371 setUTMPositionOfPerceivedObject(cpm, object, point);
1372 setMeasurementDeltaTimeOfPerceivedObject(object, delta_time);
1373}
1374
1384inline void initPerceivedObjectContainer(WrappedCpmContainer& container, const uint8_t n_objects = 0) {
1385 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER;
1386 container.container_data_perceived_object_container.number_of_perceived_objects.value = n_objects;
1387}
1388
1402inline void addPerceivedObjectToContainer(WrappedCpmContainer& container, const PerceivedObject& perceived_object) {
1403 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER) {
1404 container.container_data_perceived_object_container.perceived_objects.array.push_back(perceived_object);
1405 container.container_data_perceived_object_container.number_of_perceived_objects.value =
1406 container.container_data_perceived_object_container.perceived_objects.array.size();
1407 } else {
1408 throw std::invalid_argument("Container is not a PerceivedObjectContainer");
1409 }
1410}
1411
1424inline void addContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1425 // check for maximum number of containers
1426 if (cpm.payload.cpm_containers.value.array.size() < WrappedCpmContainers::MAX_SIZE) {
1427 cpm.payload.cpm_containers.value.array.push_back(container);
1428 } else {
1429 throw std::invalid_argument("Maximum number of CPM-Containers reached");
1430 }
1431}
1432
1441inline void setWGSRefPosConfidence(CollectivePerceptionMessage& cpm, const std::array<double, 4>& covariance_matrix) {
1442 setWGSPosConfidenceEllipse(cpm.payload.management_container.reference_position.position_confidence_ellipse,
1443 covariance_matrix);
1444}
1445
1454inline void initSensorInformationContainer(WrappedCpmContainer& container) {
1455 container.container_id.value = WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER;
1456 container.container_data_sensor_information_container.array = std::vector<SensorInformation>();
1457}
1458
1469inline void setSensorID(SensorInformation& sensor_information, const uint8_t sensor_id = 0) {
1470 throwIfOutOfRange(sensor_id, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1471 sensor_information.sensor_id.value = sensor_id;
1472}
1473
1484inline void setSensorType(SensorInformation& sensor_information, const uint8_t sensor_type = SensorType::UNDEFINED) {
1485 throwIfOutOfRange(sensor_type, SensorType::MIN, SensorType::MAX, "SensorType");
1486 sensor_information.sensor_type.value = sensor_type;
1487}
1488
1507inline void addSensorInformationToContainer(WrappedCpmContainer& container, const SensorInformation& sensor_information) {
1508 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1509 // check for maximum number of SensorInformation entries
1510 if (container.container_data_sensor_information_container.array.size() < SensorInformationContainer::MAX_SIZE ) {
1511 throwIfOutOfRange(sensor_information.sensor_id.value, Identifier1B::MIN, Identifier1B::MAX, "SensorID");
1512 throwIfOutOfRange(sensor_information.sensor_type.value, SensorType::MIN, SensorType::MAX, "SensorType");
1513 container.container_data_sensor_information_container.array.push_back(sensor_information);
1514 } else {
1515 throw std::invalid_argument("Maximum number of entries SensorInformationContainers reached");
1516 }
1517 } else {
1518 throw std::invalid_argument("Container is not a SensorInformationContainer");
1519 }
1520}
1521
1536inline void addSensorInformationContainerToCPM(CollectivePerceptionMessage& cpm, const WrappedCpmContainer& container) {
1537 if (container.container_id.value == WrappedCpmContainer::CHOICE_CONTAINER_DATA_SENSOR_INFORMATION_CONTAINER) {
1538 throwIfOutOfRange(container.container_data_sensor_information_container.array.size(),
1539 SensorInformationContainer::MIN_SIZE, SensorInformationContainer::MAX_SIZE, "SensorInformationContainer array size"
1540 );
1541 addContainerToCPM(cpm, container);
1542 } else {
1543 throw std::invalid_argument("Container is not a SensorInformationContainer");
1544 }
1545}
1546
1547} // namespace etsi_its_cpm_ts_msgs::access

◆ setXDimensionOfPerceivedObject()

void etsi_its_cpm_ts_msgs::access::setXDimensionOfPerceivedObject ( PerceivedObject & object,
const double value,
const double std = std::numeric_limits<double>::infinity() )
inline

Sets the x-dimension of a perceived object.

This function sets the x-dimension of the given PerceivedObject to the specified value. The x-dimension usually represents the length of the object.

Parameters
objectThe PerceivedObject to modify.
valueThe value to set as the x-dimension in meters.
stdThe standard deviation of the x-dimension value in meters (optional, default is infinity).

Definition at line 651 of file cpm_ts_setters.h.

◆ setYawOfPerceivedObject()

void etsi_its_cpm_ts_msgs::access::setYawOfPerceivedObject ( PerceivedObject & object,
const double yaw,
double yaw_std = std::numeric_limits<double>::infinity() )
inline

Sets the yaw angle of a perceived object.

This function sets the yaw angle of a PerceivedObject. The yaw angle is wrapped to the range [0, 360] degrees. The function also allows specifying the confidence level of the yaw angle.

Parameters
objectThe PerceivedObject to set the yaw angle for.
yawThe yaw angle in radians.
yaw_stdThe standard deviation of the yaw angle in radians (optional, default is Infinity).

Definition at line 535 of file cpm_ts_setters.h.

546 {
547 setPositionOfPerceivedObject(object, point);
549}
550

◆ setYawRateOfPerceivedObject()

void etsi_its_cpm_ts_msgs::access::setYawRateOfPerceivedObject ( PerceivedObject & object,
const double yaw_rate,
double yaw_rate_std = std::numeric_limits<double>::infinity() )
inline

Sets the yaw rate of a perceived object.

This function sets the yaw rate of a PerceivedObject. The yaw rate is limited to the range defined by CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE and CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE. The function also allows specifying the confidence level of the yaw rate.

Parameters
objectThe PerceivedObject to set the yaw rate for.
yaw_rateThe yaw rate in rad/s.
yaw_rate_stdStandard deviation of the yaw rate in rad/s (optional, default is infinity, mapping to AngularSpeedConfidence::UNAVAILABLE).

Definition at line 569 of file cpm_ts_setters.h.

596inline 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

◆ setYDimensionOfPerceivedObject()

void etsi_its_cpm_ts_msgs::access::setYDimensionOfPerceivedObject ( PerceivedObject & object,
const double value,
const double std = std::numeric_limits<double>::infinity() )
inline

Sets the y-dimension of a perceived object.

This function sets the y-dimension of the given PerceivedObject to the specified value. The y-dimension usually represents the width of the object.

Parameters
objectThe PerceivedObject to modify.
valueThe value to set as the y-dimension in meters.
stdThe standard deviation of the y-dimension value in meters (optional, default is infinity).

Definition at line 667 of file cpm_ts_setters.h.

◆ setZDimensionOfPerceivedObject()

void etsi_its_cpm_ts_msgs::access::setZDimensionOfPerceivedObject ( PerceivedObject & object,
const double value,
const double std = std::numeric_limits<double>::infinity() )
inline

Sets the z-dimension of a perceived object.

This function sets the z-dimension of the given PerceivedObject to the specified value. The z-dimension usually represents the height of the object.

Parameters
objectThe PerceivedObject to modify.
valueThe value to set as the z-dimension in meters.
stdThe standard deviation of the z-dimension value in meters (optional, default is infinity).

Definition at line 683 of file cpm_ts_setters.h.

◆ throwIfNotPresent()

void etsi_its_cpm_ts_msgs::access::throwIfNotPresent ( const bool is_present,
const std::string val_desc )
inline

Throws an exception if the given value is not present.

Parameters
is_presentWhether the value is present.
val_descDescription of the value for the exception message.

Definition at line 58 of file cpm_ts_setters.h.

◆ throwIfOutOfRange()

template<typename T1, typename T2>
void etsi_its_cpm_ts_msgs::access::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.

Template Parameters
T1
T2
Parameters
valThe value to check if it is in the range.
minThe minimum value of the range.
maxThe maximum value of the range.
val_descDescription of the value for the exception message.

Definition at line 47 of file cpm_ts_setters.h.

51 {

Variable Documentation

◆ LEAP_SECOND_INSERTIONS_SINCE_2004

const std::map<uint64_t, uint16_t> etsi_its_cpm_ts_msgs::access::etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004
Initial value:
{
{UNIX_SECONDS_2004, 0},
{1136073599, 1},
{1230767999, 2},
{1341100799, 3},
{1435708799, 4},
{1483228799, 5}
}

std::map that stores all leap second insertions since 2004 with the corresponding unix-date of the insertion

Definition at line 46 of file cpm_ts_setters.h.

51 {
52 setItsPduHeader(cpm.header, MessageId::CPM, station_id, protocol_version);
53}

◆ ONE_D_GAUSSIAN_FACTOR

const double etsi_its_cpm_ts_msgs::access::etsi_its_msgs::ONE_D_GAUSSIAN_FACTOR = 2.0
constexpr

Definition at line 72 of file cpm_ts_setters.h.

◆ TWO_D_GAUSSIAN_FACTOR

const double etsi_its_cpm_ts_msgs::access::etsi_its_msgs::TWO_D_GAUSSIAN_FACTOR = 2.4477
constexpr

Definition at line 76 of file cpm_ts_setters.h.

◆ UNIX_SECONDS_2004

const uint64_t etsi_its_cpm_ts_msgs::access::etsi_its_msgs::UNIX_SECONDS_2004 = 1072915200

Definition at line 40 of file cpm_ts_setters.h.