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.
729 {
730
732
742inline void setItsPduHeader(CollectivePerceptionMessage& cpm,
const uint32_t station_id,
743 const uint8_t protocol_version = 0) {
744 setItsPduHeader(cpm.header, MessageId::CPM, station_id, protocol_version);
745}
746
759 CollectivePerceptionMessage& cpm, const uint64_t unix_nanosecs,
760 const uint16_t n_leap_seconds = etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end()->second) {
761 TimestampIts t_its;
763 throwIfOutOfRange(t_its.value, TimestampIts::MIN, TimestampIts::MAX, "TimestampIts");
764 cpm.payload.management_container.reference_time = t_its;
765}
766
778inline void setReferencePosition(CollectivePerceptionMessage& cpm,
const double latitude,
const double longitude,
779 const double altitude = AltitudeValue::UNAVAILABLE) {
780 setReferencePosition(cpm.payload.management_container.reference_position, latitude, longitude, altitude);
781}
782
795inline void setFromUTMPosition(CollectivePerceptionMessage& cpm,
const gm::PointStamped& utm_position,
const int& zone,
796 const bool& northp) {
797 setFromUTMPosition(cpm.payload.management_container.reference_position, utm_position, zone, northp);
798}
799
809 object.object_id.value = id;
810 object.object_id_is_present = true;
811}
812
825 if (delta_time < DeltaTimeMilliSecondSigned::MIN || delta_time > DeltaTimeMilliSecondSigned::MAX) {
826 throw std::invalid_argument("MeasurementDeltaTime out of range");
827 } else {
828 object.measurement_delta_time.value = delta_time;
829 }
830}
831
846 const uint16_t confidence = CoordinateConfidence::UNAVAILABLE) {
847
848 if (value < CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE) {
849 coordinate.value.value = CartesianCoordinateLarge::NEGATIVE_OUT_OF_RANGE;
850 } else if (value > CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE) {
851 coordinate.value.value = CartesianCoordinateLarge::POSITIVE_OUT_OF_RANGE;
852 } else {
853 coordinate.value.value = value;
854 }
855
856
857 if (confidence > CoordinateConfidence::MAX || confidence < CoordinateConfidence::MIN) {
858 coordinate.confidence.value = CoordinateConfidence::OUT_OF_RANGE;
859 } else {
860 coordinate.confidence.value = confidence;
861 }
862}
863
876 const uint16_t x_confidence = CoordinateConfidence::UNAVAILABLE,
877 const uint16_t y_confidence = CoordinateConfidence::UNAVAILABLE,
878 const uint16_t z_confidence = CoordinateConfidence::UNAVAILABLE) {
881 if (point.z != 0.0) {
883 object.position.z_coordinate_is_present = true;
884 }
885}
886
903 const gm::PointStamped& utm_position,
904 const uint16_t x_confidence = CoordinateConfidence::UNAVAILABLE,
905 const uint16_t y_confidence = CoordinateConfidence::UNAVAILABLE,
906 const uint16_t z_confidence = CoordinateConfidence::UNAVAILABLE) {
908 if (utm_position.header.frame_id != reference_position.header.frame_id) {
909 throw std::invalid_argument("UTM-Position frame_id (" + utm_position.header.frame_id +
910 ") does not match the reference position frame_id (" + reference_position.header.frame_id +
911 ")");
912 }
914 (utm_position.point.x - reference_position.point.x) * 100, x_confidence);
916 (utm_position.point.y - reference_position.point.y) * 100, y_confidence);
917 if (utm_position.point.z != 0.0) {
919 (utm_position.point.z - reference_position.point.z) * 100, z_confidence);
920 object.position.z_coordinate_is_present = true;
921 }
922}
923
936 const uint8_t confidence = SpeedConfidence::UNAVAILABLE) {
937
938 if (value < VelocityComponentValue::NEGATIVE_OUT_OF_RANGE) {
939 velocity.value.value = VelocityComponentValue::NEGATIVE_OUT_OF_RANGE;
940 } else if (value > VelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
941 velocity.value.value = VelocityComponentValue::POSITIVE_OUT_OF_RANGE;
942 } else {
943 velocity.value.value = value;
944 }
945
946
947 if (confidence > SpeedConfidence::MAX || confidence < SpeedConfidence::MIN) {
948 velocity.confidence.value = SpeedConfidence::OUT_OF_RANGE;
949 } else {
950 velocity.confidence.value = confidence;
951 }
952}
953
967 const uint8_t x_confidence = SpeedConfidence::UNAVAILABLE,
968 const uint8_t y_confidence = SpeedConfidence::UNAVAILABLE,
969 const uint8_t z_confidence = SpeedConfidence::UNAVAILABLE) {
970 object.velocity.choice = Velocity3dWithConfidence::CHOICE_CARTESIAN_VELOCITY;
971 setVelocityComponent(
object.velocity.cartesian_velocity.x_velocity, cartesian_velocity.x * 100, x_confidence * 100);
972 setVelocityComponent(
object.velocity.cartesian_velocity.y_velocity, cartesian_velocity.y * 100, y_confidence * 100);
973 if (cartesian_velocity.z != 0.0) {
974 setVelocityComponent(
object.velocity.cartesian_velocity.z_velocity, cartesian_velocity.z * 100, z_confidence * 100);
975 object.velocity.cartesian_velocity.z_velocity_is_present = true;
976 }
977 object.velocity_is_present = true;
978}
979
992 const uint8_t confidence = AccelerationConfidence::UNAVAILABLE) {
993
994 if (value < AccelerationValue::NEGATIVE_OUT_OF_RANGE) {
995 acceleration.value.value = AccelerationValue::NEGATIVE_OUT_OF_RANGE;
996 } else if (value > AccelerationValue::POSITIVE_OUT_OF_RANGE) {
997 acceleration.value.value = AccelerationValue::POSITIVE_OUT_OF_RANGE;
998 } else {
999 acceleration.value.value = value;
1000 }
1001
1002
1003 if (confidence > AccelerationConfidence::MAX || confidence < AccelerationConfidence::MIN) {
1004 acceleration.confidence.value = AccelerationConfidence::OUT_OF_RANGE;
1005 } else {
1006 acceleration.confidence.value = confidence;
1007 }
1008}
1009
1023 const uint8_t x_confidence = AccelerationConfidence::UNAVAILABLE,
1024 const uint8_t y_confidence = AccelerationConfidence::UNAVAILABLE,
1025 const uint8_t z_confidence = AccelerationConfidence::UNAVAILABLE) {
1026 object.acceleration.choice = Acceleration3dWithConfidence::CHOICE_CARTESIAN_ACCELERATION;
1028 x_confidence * 10);
1030 y_confidence * 10);
1031 if (cartesian_acceleration.z != 0.0) {
1033 z_confidence * 10);
1034 object.acceleration.cartesian_acceleration.z_acceleration_is_present = true;
1035 }
1036 object.acceleration_is_present = true;
1037}
1038
1050 const uint8_t confidence = AngleConfidence::UNAVAILABLE) {
1051
1052 double yaw_in_degrees = yaw * 180 / M_PI + 180;
1053 while (yaw_in_degrees > 360.0) yaw_in_degrees -= 360.0;
1054 while (yaw_in_degrees < 0) yaw_in_degrees += 360.0;
1055 object.angles.z_angle.value.value = yaw_in_degrees * 10;
1056
1057 if (confidence > AngleConfidence::MAX || confidence < AngleConfidence::MIN) {
1058 object.angles.z_angle.confidence.value = AngleConfidence::OUT_OF_RANGE;
1059 } else {
1060 object.angles.z_angle.confidence.value = confidence;
1061 }
1062 object.angles_is_present = true;
1063}
1064
1077 const uint8_t confidence = AngularSpeedConfidence::UNAVAILABLE) {
1078 int16_t yaw_rate_in_degrees = yaw_rate * 180 / M_PI;
1079 if (yaw_rate_in_degrees != CartesianAngularVelocityComponentValue::UNAVAILABLE) {
1080
1081 if (yaw_rate_in_degrees < CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE) {
1082 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::NEGATIVE_OUTOF_RANGE;
1083 } else if (yaw_rate_in_degrees > CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE) {
1084 yaw_rate_in_degrees = CartesianAngularVelocityComponentValue::POSITIVE_OUT_OF_RANGE;
1085 }
1086 }
1087 object.z_angular_velocity.value.value = yaw_rate_in_degrees;
1088 object.z_angular_velocity.confidence.value = confidence;
1089 object.z_angular_velocity_is_present = true;
1090}
1091
1107 const uint8_t confidence = ObjectDimensionConfidence::UNAVAILABLE) {
1108
1109 if (value < ObjectDimensionValue::MIN || value > ObjectDimensionValue::MAX) {
1110 dimension.value.value = ObjectDimensionValue::OUT_OF_RANGE;
1111 } else {
1112 dimension.value.value = value;
1113 }
1114
1115
1116 if (confidence > ObjectDimensionConfidence::MAX || confidence < ObjectDimensionConfidence::MIN) {
1117 dimension.confidence.value = ObjectDimensionConfidence::OUT_OF_RANGE;
1118 } else {
1119 dimension.confidence.value = confidence;
1120 }
1121}
1122
1134 const uint8_t confidence = ObjectDimensionConfidence::UNAVAILABLE) {
1135 setObjectDimension(
object.object_dimension_x, (uint16_t)(value * 10), confidence * 10);
1136 object.object_dimension_x_is_present = true;
1137}
1138
1150 const uint8_t confidence = ObjectDimensionConfidence::UNAVAILABLE) {
1151 setObjectDimension(
object.object_dimension_y, (uint16_t)(value * 10), confidence * 10);
1152 object.object_dimension_y_is_present = true;
1153}
1154
1166 const uint8_t confidence = ObjectDimensionConfidence::UNAVAILABLE) {
1167 setObjectDimension(
object.object_dimension_z, (uint16_t)(value * 10), confidence * 10);
1168 object.object_dimension_z_is_present = true;
1169}
1170
1183 const uint8_t x_confidence = ObjectDimensionConfidence::UNAVAILABLE,
1184 const uint8_t y_confidence = ObjectDimensionConfidence::UNAVAILABLE,
1185 const uint8_t z_confidence = ObjectDimensionConfidence::UNAVAILABLE) {
1189}
1190
1200inline void initPerceivedObject(PerceivedObject&
object,
const gm::Point& point,
const int16_t delta_time = 0) {
1203}
1204
1218 const gm::PointStamped& point, const int16_t delta_time = 0) {
1221}
1222
1233 container.container_id.value = CpmContainerId::PERCEIVED_OBJECT_CONTAINER;
1234 container.container_data.choice = container.container_id;
1235 container.container_data.perceived_object_container.number_of_perceived_objects.value = n_objects;
1236}
1237
1252 if (container.container_id.value == CpmContainerId::PERCEIVED_OBJECT_CONTAINER &&
1253 container.container_data.choice.value == CpmContainerId::PERCEIVED_OBJECT_CONTAINER) {
1254 container.container_data.perceived_object_container.perceived_objects.array.push_back(perceived_object);
1255 container.container_data.perceived_object_container.number_of_perceived_objects.value =
1256 container.container_data.perceived_object_container.perceived_objects.array.size();
1257 } else {
1258 throw std::invalid_argument("Container is not a PerceivedObjectContainer");
1259 }
1260}
1261
1274inline void addContainerToCPM(CollectivePerceptionMessage& cpm,
const WrappedCpmContainer& container) {
1275
1276 if (cpm.payload.cpm_containers.value.array.size() < WrappedCpmContainers::MAX_SIZE) {
1277 cpm.payload.cpm_containers.value.array.push_back(container);
1278 } else {
1279 throw std::invalid_argument("Maximum number of CPM-Containers reached");
1280 }
1281}
1282
1283}
gm::PointStamped getUTMPosition(const CAM &cam, int &zone, bool &northp)
Get the UTM Position defined within the BasicContainer of the CAM.
void setFromUTMPosition(CAM &cam, const gm::PointStamped &utm_position, const int &zone, const bool &northp)
Set the ReferencePosition of a CAM from a given UTM-Position.
void setReferencePosition(CAM &cam, const double latitude, const double longitude, const double altitude=AltitudeValue::UNAVAILABLE)
Set the ReferencePosition for a CAM.
void setTimestampITS(TimestampIts ×tamp_its, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end() ->second)
Set the TimestampITS 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.
Setter functions for the ETSI ITS Common Data Dictionary (CDD) v2.1.1.
void setCartesianCoordinateWithConfidence(CartesianCoordinateWithConfidence &coordinate, const int32_t value, const uint16_t confidence=CoordinateConfidence::UNAVAILABLE)
Sets the value and confidence of a CartesianCoordinateWithConfidence object.
void setDimensionsOfPerceivedObject(PerceivedObject &object, const gm::Vector3 &dimensions, const uint8_t x_confidence=ObjectDimensionConfidence::UNAVAILABLE, const uint8_t y_confidence=ObjectDimensionConfidence::UNAVAILABLE, const uint8_t z_confidence=ObjectDimensionConfidence::UNAVAILABLE)
Sets all dimensions of a perceived object.
void setUTMPositionOfPerceivedObject(CollectivePerceptionMessage &cpm, PerceivedObject &object, const gm::PointStamped &utm_position, const uint16_t x_confidence=CoordinateConfidence::UNAVAILABLE, const uint16_t y_confidence=CoordinateConfidence::UNAVAILABLE, const uint16_t z_confidence=CoordinateConfidence::UNAVAILABLE)
Sets the position of a perceived object based on a UTM position.
void setVelocityComponent(VelocityComponent &velocity, const int16_t value, const uint8_t confidence=SpeedConfidence::UNAVAILABLE)
Sets the value and confidence of a VelocityComponent.
void initPerceivedObjectContainer(WrappedCpmContainer &container, const uint8_t n_objects=0)
Initializes a WrappedCpmContainer as a PerceivedObjectContainer with the given number of objects.
void setYDimensionOfPerceivedObject(PerceivedObject &object, const double value, const uint8_t confidence=ObjectDimensionConfidence::UNAVAILABLE)
Sets the y-dimension of a perceived object.
void addPerceivedObjectToContainer(WrappedCpmContainer &container, const PerceivedObject &perceived_object)
Adds a PerceivedObject to the PerceivedObjectContainer / WrappedCpmContainer.
void setObjectDimension(ObjectDimension &dimension, const uint16_t value, const uint8_t confidence=ObjectDimensionConfidence::UNAVAILABLE)
Sets the object dimension with the given value and confidence.
void addContainerToCPM(CollectivePerceptionMessage &cpm, const WrappedCpmContainer &container)
Adds a container to the Collective Perception Message (CPM).
void setIdOfPerceivedObject(PerceivedObject &object, const uint16_t id)
Set the ID of a PerceivedObject.
void setReferenceTime(CollectivePerceptionMessage &cpm, const uint64_t unix_nanosecs, const uint16_t n_leap_seconds=etsi_its_msgs::LEAP_SECOND_INSERTIONS_SINCE_2004.end() ->second)
Sets the reference time in a CPM.
void setYawOfPerceivedObject(PerceivedObject &object, const double yaw, const uint8_t confidence=AngleConfidence::UNAVAILABLE)
Sets the yaw angle of a perceived object.
void setXDimensionOfPerceivedObject(PerceivedObject &object, const double value, const uint8_t confidence=ObjectDimensionConfidence::UNAVAILABLE)
Sets the x-dimension of a perceived object.
void setMeasurementDeltaTimeOfPerceivedObject(PerceivedObject &object, const int16_t delta_time=0)
Sets the measurement delta time of a PerceivedObject.
void setVelocityOfPerceivedObject(PerceivedObject &object, const gm::Vector3 &cartesian_velocity, const uint8_t x_confidence=SpeedConfidence::UNAVAILABLE, const uint8_t y_confidence=SpeedConfidence::UNAVAILABLE, const uint8_t z_confidence=SpeedConfidence::UNAVAILABLE)
void setAccelerationOfPerceivedObject(PerceivedObject &object, const gm::Vector3 &cartesian_acceleration, const uint8_t x_confidence=AccelerationConfidence::UNAVAILABLE, const uint8_t y_confidence=AccelerationConfidence::UNAVAILABLE, const uint8_t z_confidence=AccelerationConfidence::UNAVAILABLE)
Sets the acceleration of a perceived object.
void setPositionOfPerceivedObject(PerceivedObject &object, const gm::Point &point, const uint16_t x_confidence=CoordinateConfidence::UNAVAILABLE, const uint16_t y_confidence=CoordinateConfidence::UNAVAILABLE, const uint16_t z_confidence=CoordinateConfidence::UNAVAILABLE)
Sets the position of a perceived object (relative to the CPM's reference position).
void setYawRateOfPerceivedObject(PerceivedObject &object, const double yaw_rate, const uint8_t confidence=AngularSpeedConfidence::UNAVAILABLE)
Sets the yaw rate of a perceived object.
void setZDimensionOfPerceivedObject(PerceivedObject &object, const double value, const uint8_t confidence=ObjectDimensionConfidence::UNAVAILABLE)
Sets the z-dimension of a perceived object.
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 setAccelerationComponent(AccelerationComponent &acceleration, const int16_t value, const uint8_t confidence=AccelerationConfidence::UNAVAILABLE)
Sets the value and confidence of a AccelerationComponent.
void initPerceivedObject(PerceivedObject &object, const gm::Point &point, const int16_t delta_time=0)
Initializes a PerceivedObject with the given point and delta time.