diff --git a/Arduino/V1_6_Sensoren_mit_LPn_Control_Vincent/V1_6_Sensoren_mit_LPn_Control_Vincent.ino b/Arduino/V1_6_Sensoren_mit_LPn_Control_Vincent/V1_6_Sensoren_mit_LPn_Control_Vincent.ino index 51f87f401ec6353b979ce4c46c2e74d12b312724..d429797375e9778819a831715079262e413fd5b1 100644 --- a/Arduino/V1_6_Sensoren_mit_LPn_Control_Vincent/V1_6_Sensoren_mit_LPn_Control_Vincent.ino +++ b/Arduino/V1_6_Sensoren_mit_LPn_Control_Vincent/V1_6_Sensoren_mit_LPn_Control_Vincent.ino @@ -78,7 +78,7 @@ pin_size_t SDA_PIN0 = 20; pin_size_t SCL_PIN0 = 21; int sensor_count = 0; -bool sensorInitialized[8] = { false }; // global oder static +bool sensorInitialized[28] = { false }; // global oder static JsonDocument doc; diff --git a/Bachelorarbeit/Exported Items.bib b/Bachelorarbeit/Exported Items.bib new file mode 100644 index 0000000000000000000000000000000000000000..14f3ddb8d76363718f540edc4e457be0a7c0691e --- /dev/null +++ b/Bachelorarbeit/Exported Items.bib @@ -0,0 +1,10 @@ + +@misc{noauthor_din_nodate, + address = {Berlin}, + title = {{DIN} {EN} {ISO} 13855:2022-04, {Sicherheit} von {Maschinen}\_- {Anordnung} von {Schutzeinrichtungen} im {Hinblick} auf {Annäherung} des menschlichen {Körpers} ({ISO}/{DIS}\_13855:2022); {Deutsche} und {Englische} {Fassung} {prEN}\_ISO\_13855:2022}, + shorttitle = {{DIN} {EN} {ISO} 13855}, + url = {https://www.dinmedia.de/de/-/-/349862066}, + doi = {10.31030/3329034}, + urldate = {2025-05-23}, + publisher = {DIN Media GmbH}, +} diff --git a/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/moveit_stop_node.py b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/moveit_stop_node.py index f8c2f853566a6fc5546a8cd0a1c51008aa49ebbc..e89a7d5d4a426d14f9998c1bbd8cd64867b2ce1e 100644 --- a/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/moveit_stop_node.py +++ b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/moveit_stop_node.py @@ -70,6 +70,7 @@ class PointCloudProcessor(Node): def pointcloud_callback(self, msg): self.perspective_frame = 'vl53l7cx_link' + self.stamp = msg.header.stamp try: now = rclpy.time.Time() transforms = { @@ -111,6 +112,9 @@ class PointCloudProcessor(Node): def stop_trajectory(self): self.get_logger().info("Stopping trajectory execution due to point cloud threshold.") + ros_time = self.get_clock().now().to_msg() + time_diff = (ros_time.sec + ros_time.nanosec * 1e-9) - (self.stamp.sec + self.stamp.nanosec * 1e-9) + self.get_logger().info(f"Time difference between ROS time and pointcloud stamp: {time_diff:.6f} seconds") cancel_string = String() cancel_string.data = "stop" self.cancellation_pub.publish(cancel_string) @@ -129,6 +133,7 @@ class PointCloudProcessor(Node): for i, n in enumerate('xyz')] # Define the fields for x, y, and z header = Header(frame_id=parent_frame) # Create a header with the parent frame + header.stamp = self.stamp # Set the timestamp return PointCloud2( header=header, height=1, # Single row of points diff --git a/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/pcl_filter_node.py b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/pcl_filter_node.py index 0a568b4b15a5bb1116c0c5ffb30b9020180c80b0..9740d9167b7b65ce2d0530417d916996dae1f4f4 100644 --- a/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/pcl_filter_node.py +++ b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/pcl_filter_node.py @@ -65,6 +65,7 @@ class PointCloudProcessor(Node): def pointcloud_callback(self, msg): self.perspective_frame = 'vl53l7cx_link' + self.stamp = msg.header.stamp try: now = rclpy.time.Time() transforms = { @@ -118,6 +119,7 @@ class PointCloudProcessor(Node): data = points.astype(dtype).tobytes() fields = [sensor_msgs.PointField(name=n, offset=i * itemsize, datatype=ros_dtype, count=1) for i, n in enumerate('xyz')] header = Header(frame_id=parent_frame) + header.stamp = self.stamp return sensor_msgs.PointCloud2( header=header, diff --git a/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/serial_to_pcl_node.py b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/serial_to_pcl_node.py index c90f25e3a9e8077b1b94eda746628fca41e8dd16..40aa73f641cfcdfc56f5ff31737e6306d6d6ba44 100644 --- a/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/serial_to_pcl_node.py +++ b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/serial_to_pcl_node.py @@ -49,6 +49,7 @@ class SerialListPublisher(Node): """ try: while rclpy.ok(): # Keep running while ROS 2 is active + self.stamp = self.get_clock().now().to_msg() # Get the current timestamp line = self.serial_port.readline().decode('utf-8').strip() # Read a line from the serial port data = self.parse_json(line) # Parse the JSON data if not data: # Skip if the data is invalid @@ -229,6 +230,7 @@ class SerialListPublisher(Node): for i, n in enumerate('xyz')] # Define the fields for x, y, and z header = Header(frame_id=parent_frame) # Create a header with the parent frame + header.stamp = self.stamp return PointCloud2( header=header, height=1, # Single row of points @@ -240,22 +242,6 @@ class SerialListPublisher(Node): row_step=(itemsize * 3 * points.shape[0]), # Size of each row in bytes data=data # Binary data for the points ) - def create_empty_point_cloud(self): - """ - Create an empty PointCloud2 message. - """ - header = Header(frame_id=self.parent_frame) - return PointCloud2( - header=header, - height=1, - width=0, - is_dense=True, - is_bigendian=False, - fields=[], - point_step=0, - row_step=0, - data=b'' - ) def main(args=None): """