28 from rclpy.node
import Node
37 topic =
"/etsi_its_conversion/cpm_ts/in"
38 self.
publisher = self.create_publisher(CollectivePerceptionMessage, topic, 1)
43 msg = CollectivePerceptionMessage()
45 msg.header.protocol_version.value = 2
46 msg.header.message_id.value = msg.header.message_id.CPM
48 msg.payload.management_container.reference_time.value =
utils.get_t_its(self.get_clock().now().nanoseconds)
49 msg.payload.management_container.reference_position.latitude.value = int(50.78779641723146 * 1e7)
50 msg.payload.management_container.reference_position.longitude.value = int(6.047076274316094 * 1e7)
53 cpm_container = WrappedCpmContainer()
54 cpm_container.container_id.value = cpm_container.CHOICE_CONTAINER_DATA_PERCEIVED_OBJECT_CONTAINER
56 perceived_object_container = PerceivedObjectContainer()
57 perceived_object_container.number_of_perceived_objects.value = 2
58 for i
in range(perceived_object_container.number_of_perceived_objects.value):
59 perceived_object = PerceivedObject()
60 perceived_object.object_id_is_present =
True
61 perceived_object.object_id.value = i
62 perceived_object.measurement_delta_time.value = 10
63 perceived_object.position.x_coordinate.value.value = int(10 * 1e2 * (i*3))
64 perceived_object.position.x_coordinate.confidence.value = perceived_object.position.x_coordinate.confidence.UNAVAILABLE
65 perceived_object.position.y_coordinate.value.value = int(2 * 1e2)
66 perceived_object.position.y_coordinate.confidence.value = perceived_object.position.y_coordinate.confidence.UNAVAILABLE
67 perceived_object.object_dimension_x_is_present =
True
68 perceived_object.object_dimension_x.value.value = int(3.5 * 1e1)
69 perceived_object.object_dimension_x.confidence.value = perceived_object.object_dimension_x.confidence.UNAVAILABLE
70 perceived_object.object_dimension_y_is_present =
True
71 perceived_object.object_dimension_y.value.value = int(1.8 * 1e1)
72 perceived_object.object_dimension_y.confidence.value = perceived_object.object_dimension_y.confidence.UNAVAILABLE
73 perceived_object.object_dimension_z_is_present =
True
74 perceived_object.object_dimension_z.value.value = int(1.6 * 1e1)
75 perceived_object.object_dimension_z.confidence.value = perceived_object.object_dimension_z.confidence.UNAVAILABLE
76 perceived_object_container.perceived_objects.array.append(perceived_object)
78 cpm_container.container_data_perceived_object_container = perceived_object_container
79 msg.payload.cpm_containers.value.array.append(cpm_container)
81 self.get_logger().info(f
"Publishing CPM")
84 if __name__ ==
"__main__":