diff --git a/Install Documentation/comand_cheat_sheet b/Install Documentation/comand_cheat_sheet
index 5ae534763837b5a4227ffe4248166d67b9ef95fa..ae626e4905c7231b70d8d6a6787f6a967c64e8d4 100644
--- a/Install Documentation/comand_cheat_sheet	
+++ b/Install Documentation/comand_cheat_sheet	
@@ -1,5 +1,5 @@
 cd robot-sensor/workspaces/COLCON_WS
 source install/setup.bash
-ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur10 robot_ip:=192.168.1.2 description_package:=custom_ur_description
+ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur10 robot_ip:=192.168.1.2
 ros2 launch ur_moveit_config ur_moveit.launch.py ur_type:=ur10 launch_rviz:=true
 
diff --git a/Progress_Documentation/Screencast from 05-09-2025 07:10:23 PM.webm b/Progress_Documentation/Screencast from 05-09-2025 07:10:23 PM.webm
new file mode 100644
index 0000000000000000000000000000000000000000..ce86777ce719b3c645426fc638df1b8a829c6e0c
Binary files /dev/null and b/Progress_Documentation/Screencast from 05-09-2025 07:10:23 PM.webm differ
diff --git a/Progress_Documentation/Screencast from 05-09-2025 07:11:43 PM.webm b/Progress_Documentation/Screencast from 05-09-2025 07:11:43 PM.webm
new file mode 100644
index 0000000000000000000000000000000000000000..9c98d56bd774677cae09f7f4d9730f5727266dd2
Binary files /dev/null and b/Progress_Documentation/Screencast from 05-09-2025 07:11:43 PM.webm differ
diff --git a/Progress_Documentation/Screencast from 05-09-2025 07:12:38 PM.webm b/Progress_Documentation/Screencast from 05-09-2025 07:12:38 PM.webm
new file mode 100644
index 0000000000000000000000000000000000000000..5ca917fc13beec068bb46006273b271ad5dcd6a5
Binary files /dev/null and b/Progress_Documentation/Screencast from 05-09-2025 07:12:38 PM.webm differ
diff --git a/Progress_Documentation/Screencast from 05-09-2025 07:13:29 PM.webm b/Progress_Documentation/Screencast from 05-09-2025 07:13:29 PM.webm
new file mode 100644
index 0000000000000000000000000000000000000000..b42ecdc69d99661534e8d38d387c34fb57988055
Binary files /dev/null and b/Progress_Documentation/Screencast from 05-09-2025 07:13:29 PM.webm differ
diff --git a/Progress_Documentation/Screencast from 05-09-2025 07:15:21 PM.webm b/Progress_Documentation/Screencast from 05-09-2025 07:15:21 PM.webm
new file mode 100644
index 0000000000000000000000000000000000000000..8b366c5b59281f69d0bf0e5fd54e19aad544e556
Binary files /dev/null and b/Progress_Documentation/Screencast from 05-09-2025 07:15:21 PM.webm differ
diff --git a/Progress_Documentation/Screencast from 05-09-2025 07:16:25 PM.webm b/Progress_Documentation/Screencast from 05-09-2025 07:16:25 PM.webm
new file mode 100644
index 0000000000000000000000000000000000000000..3a1d993222f9aabae68779232205a4d93d4a4c51
Binary files /dev/null and b/Progress_Documentation/Screencast from 05-09-2025 07:16:25 PM.webm differ
diff --git a/workspaces/COLCON_WS/src/Universal_Robots_ROS2_Gazebo_Simulation/ur_simulation_gazebo/launch/ur_sim_moveit.launch.py b/workspaces/COLCON_WS/src/Universal_Robots_ROS2_Gazebo_Simulation/ur_simulation_gazebo/launch/ur_sim_moveit.launch.py
deleted file mode 100644
index 360235313897744fd5c098b06b522b280e6db2c1..0000000000000000000000000000000000000000
--- a/workspaces/COLCON_WS/src/Universal_Robots_ROS2_Gazebo_Simulation/ur_simulation_gazebo/launch/ur_sim_moveit.launch.py
+++ /dev/null
@@ -1,168 +0,0 @@
-# Copyright (c) 2022 Stogl Robotics Consulting UG (haftungsbeschränkt)
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions are met:
-#
-#    * Redistributions of source code must retain the above copyright
-#      notice, this list of conditions and the following disclaimer.
-#
-#    * Redistributions in binary form must reproduce the above copyright
-#      notice, this list of conditions and the following disclaimer in the
-#      documentation and/or other materials provided with the distribution.
-#
-#    * Neither the name of the {copyright_holder} nor the names of its
-#      contributors may be used to endorse or promote products derived from
-#      this software without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
-# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
-# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
-# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
-# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
-# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
-# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
-# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
-# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
-# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-# Author: Denis Stogl
-
-from launch import LaunchDescription
-from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, OpaqueFunction
-from launch.launch_description_sources import PythonLaunchDescriptionSource
-from launch.substitutions import LaunchConfiguration
-from launch_ros.substitutions import FindPackageShare
-
-
-def launch_setup(context, *args, **kwargs):
-
-    # Initialize Arguments
-    ur_type = LaunchConfiguration("ur_type")
-    safety_limits = LaunchConfiguration("safety_limits")
-    # General arguments
-    runtime_config_package = LaunchConfiguration("runtime_config_package")
-    controllers_file = LaunchConfiguration("controllers_file")
-    description_package = LaunchConfiguration("description_package")
-    description_file = LaunchConfiguration("description_file")
-    moveit_config_package = LaunchConfiguration("moveit_config_package")
-    moveit_config_file = LaunchConfiguration("moveit_config_file")
-    prefix = LaunchConfiguration("prefix")
-
-    ur_control_launch = IncludeLaunchDescription(
-        PythonLaunchDescriptionSource(
-            [FindPackageShare("ur_simulation_gazebo"), "/launch", "/ur_sim_control.launch.py"]
-        ),
-        launch_arguments={
-            "ur_type": ur_type,
-            "safety_limits": safety_limits,
-            "runtime_config_package": runtime_config_package,
-            "controllers_file": controllers_file,
-            "description_package": description_package,
-            "description_file": description_file,
-            "prefix": prefix,
-            "launch_rviz": "false",
-        }.items(),
-    )
-
-    ur_moveit_launch = IncludeLaunchDescription(
-        PythonLaunchDescriptionSource(
-            [FindPackageShare("ur_moveit_config"), "/launch", "/ur_moveit.launch.py"]
-        ),
-        launch_arguments={
-            "ur_type": ur_type,
-            "safety_limits": safety_limits,
-            "description_package": description_package,
-            "description_file": description_file,
-            "moveit_config_package": moveit_config_package,
-            "moveit_config_file": moveit_config_file,
-            "prefix": prefix,
-            "use_sim_time": "true",
-            "launch_rviz": "true",
-            "use_fake_hardware": "true",  # to change moveit default controller to joint_trajectory_controller
-        }.items(),
-    )
-
-    nodes_to_launch = [
-        ur_control_launch,
-        ur_moveit_launch,
-    ]
-
-    return nodes_to_launch
-
-
-def generate_launch_description():
-    declared_arguments = []
-    # UR specific arguments
-    declared_arguments.append(
-        DeclareLaunchArgument(
-            "ur_type",
-            description="Type/series of used UR robot.",
-            choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20", "ur30"],
-            default_value="ur10",
-        )
-    )
-    declared_arguments.append(
-        DeclareLaunchArgument(
-            "safety_limits",
-            default_value="true",
-            description="Enables the safety limits controller if true.",
-        )
-    )
-    # General arguments
-    declared_arguments.append(
-        DeclareLaunchArgument(
-            "runtime_config_package",
-            default_value="ur_simulation_gazebo",
-            description='Package with the controller\'s configuration in "config" folder. \
-        Usually the argument is not set, it enables use of a custom setup.',
-        )
-    )
-    declared_arguments.append(
-        DeclareLaunchArgument(
-            "controllers_file",
-            default_value="ur_controllers.yaml",
-            description="YAML file with the controllers configuration.",
-        )
-    )
-    declared_arguments.append(
-        DeclareLaunchArgument(
-            "description_package",
-            default_value="custom_ur_description",
-            description="Description package with robot URDF/XACRO files. Usually the argument \
-        is not set, it enables use of a custom description.",
-        )
-    )
-    declared_arguments.append(
-        DeclareLaunchArgument(
-            "description_file",
-            default_value="ur.urdf.xacro",
-            description="URDF/XACRO description file with the robot.",
-        )
-    )
-    declared_arguments.append(
-        DeclareLaunchArgument(
-            "moveit_config_package",
-            default_value="ur_moveit_config",
-            description="MoveIt config package with robot SRDF/XACRO files. Usually the argument \
-        is not set, it enables use of a custom moveit config.",
-        )
-    )
-    declared_arguments.append(
-        DeclareLaunchArgument(
-            "moveit_config_file",
-            default_value="ur.srdf.xacro",
-            description="MoveIt SRDF/XACRO description file with the robot.",
-        )
-    )
-    declared_arguments.append(
-        DeclareLaunchArgument(
-            "prefix",
-            default_value='""',
-            description="Prefix of the joint names, useful for \
-        multi-robot setup. If changed than also joint names in the controllers' configuration \
-        have to be updated.",
-        )
-    )
-
-    return LaunchDescription(declared_arguments + [OpaqueFunction(function=launch_setup)])
diff --git a/workspaces/COLCON_WS/src/ser_test/package.xml b/workspaces/COLCON_WS/src/serial_to_pcl/package.xml
similarity index 91%
rename from workspaces/COLCON_WS/src/ser_test/package.xml
rename to workspaces/COLCON_WS/src/serial_to_pcl/package.xml
index b7ca9374fc0ac32930a3cfa10b1bdf6b5e70a32f..4abfc908eca66846628362c1c2e38b98ac8d4998 100644
--- a/workspaces/COLCON_WS/src/ser_test/package.xml
+++ b/workspaces/COLCON_WS/src/serial_to_pcl/package.xml
@@ -1,6 +1,6 @@
 <?xml version="1.0"?>
 <package format="2">
-    <name>ser_test</name>
+    <name>serial_to_pcl</name>
     <version>0.0.1</version>
     <description>ROS 2 package for serial communication testing</description>
 
@@ -14,7 +14,6 @@
     <exec_depend>sensor_msgs</exec_depend>
     <exec_depend>numpy</exec_depend>
     <exec_depend>pyserial</exec_depend>
-    <exec_depend>json</exec_depend>
 
     <test_depend>ament_lint_auto</test_depend>
     <test_depend>ament_lint_common</test_depend>
diff --git a/workspaces/COLCON_WS/src/ser_test/resource/ser_test b/workspaces/COLCON_WS/src/serial_to_pcl/resource/serial_to_pcl
similarity index 100%
rename from workspaces/COLCON_WS/src/ser_test/resource/ser_test
rename to workspaces/COLCON_WS/src/serial_to_pcl/resource/serial_to_pcl
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/__init__.py b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/__init__.py
similarity index 100%
rename from workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/__init__.py
rename to workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/__init__.py
diff --git a/workspaces/COLCON_WS/src/ser_test/ser_test/pcl_rob_node.py b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/pcl_rob_node.py
similarity index 100%
rename from workspaces/COLCON_WS/src/ser_test/ser_test/pcl_rob_node.py
rename to workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/pcl_rob_node.py
diff --git a/workspaces/COLCON_WS/src/ser_test/ser_test/pcl_rob_v2_node.py b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/pcl_rob_v2_node.py
similarity index 84%
rename from workspaces/COLCON_WS/src/ser_test/ser_test/pcl_rob_v2_node.py
rename to workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/pcl_rob_v2_node.py
index 7d59b443ef63f23c5309783c584a0afa743a7095..0421526458b439093fd14567ed44efb44d8eb74e 100644
--- a/workspaces/COLCON_WS/src/ser_test/ser_test/pcl_rob_v2_node.py
+++ b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/pcl_rob_v2_node.py
@@ -34,9 +34,8 @@ class PointCloudMeshChecker(Node):
         self.mesh_wrist1_link_static = trimesh.load_mesh(os.path.join(base_path, 'wrist1.stl'))
         self.mesh_wrist2_link_static = trimesh.load_mesh(os.path.join(base_path, 'wrist2.stl'))
         self.mesh_wrist3_link_static = trimesh.load_mesh(os.path.join(base_path, 'wrist3.stl'))
-
-        base_path_collision = os.path.join(os.path.expanduser('~'), 'robot-sensor', 'workspaces', 'COLCON_WS', 'src', 'ur_description', 'meshes', 'ur10', 'collision')
-        self.mesh_base_link_static = trimesh.load_mesh(os.path.join(base_path_collision, 'base.stl'))
+        self.mesh_base_link_static = trimesh.load_mesh(os.path.join(base_path, 'base.stl'))
+        
         # Create a dictionary with frames as keys and corresponding static meshes as values
         self.frame_to_mesh_map = {
             'shoulder_link': self.mesh_shoulder_link_static,
@@ -70,32 +69,26 @@ class PointCloudMeshChecker(Node):
 
     def pointcloud_callback(self, msg):
         try:
+            # Read the point cloud data
             self.points_original = np.array([(point['x'], point['y'], point['z']) for point in pc2.read_points(msg, field_names=("x", "y", "z"), skip_nans=True)], dtype=np.float64)
             for frame in self.target_frames:
-                try:
-                    transform = self.tf_buffer.lookup_transform(self.perspective_frame, frame, rclpy.time.Time())
-                except Exception as e:
-                    self.get_logger().error(f'Error looking up transform from {self.perspective_frame} to {frame}: {e}')
-                    continue
-                try:
-                    # Transform the point cloud to the perspective frame
-                    transformed_points = self.do_transform_cloud(msg, transform.transform)
-                    inside_robot = self.check_points_in_mesh(transformed_points, frame)
-                except Exception as e:
-                    self.get_logger().error(f'Error transforming point cloud: {e}')
-                    continue
+                transform = self.tf_buffer.lookup_transform(self.perspective_frame, frame, rclpy.time.Time())
+
+                # Transform the point cloud to the perspective frame
+                transformed_points = self.do_transform_cloud(msg, transform.transform)
+                inside_robot = self.check_points_in_mesh(transformed_points, frame)
+                self.get_logger().info(f"Frame: {frame}, Points inside robot: {np.sum(inside_robot)}")
 
                 if frame not in self.inside_robot_dict:
                     self.inside_robot_dict[frame] = None
                 self.inside_robot_dict[frame] = inside_robot
 
             self.list_inside_robot = [self.inside_robot_dict[frame] for frame in self.target_frames if frame in self.inside_robot_dict]
-
-            inside_all_frames = np.logical_and.reduce(self.list_inside_robot) if self.list_inside_robot else np.zeros(len(self.points_original), dtype=bool)
+            inside_all_frames = np.logical_or.reduce(self.list_inside_robot) if self.list_inside_robot else np.zeros(len(self.points_original), dtype=bool)
             points_inside_robot = self.points_original[inside_all_frames]
             points_outside_robot = self.points_original[~inside_all_frames]
             # Publish the point clouds
-            #self.publish_point_cloud(points_outside_robot, points_inside_robot)
+            self.publish_point_cloud(points_outside_robot, points_inside_robot)
         except Exception as e:
             self.get_logger().error(f'Error processing point cloud: {e}')
 
@@ -134,12 +127,6 @@ class PointCloudMeshChecker(Node):
             self.frame_to_mesh_map['shoulder_link'].contains(points_array)
         ))
 
-        # Get points inside the robot
-        points_inside_robot = self.points_original[inside_robot]
-        # Get points outside the robot
-        points_outside_robot = self.points_original[~inside_robot]
-        self.publish_point_cloud(points_outside_robot, points_inside_robot)
-
         return inside_robot
 
 
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
new file mode 100644
index 0000000000000000000000000000000000000000..406dc0c018067ad6d9a1ef4e9ced4edacd4e5d9a
--- /dev/null
+++ b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/serial_to_pcl_node.py
@@ -0,0 +1,274 @@
+import serial  # For serial communication with the sensor
+import rclpy  # ROS 2 Python client library
+import json  # For parsing JSON data from the sensor
+import numpy as np  # For numerical operations
+from rclpy.node import Node  # Base class for ROS 2 nodes
+from sensor_msgs.msg import PointCloud2, PointField  # ROS 2 message types for point clouds
+from std_msgs.msg import Header  # ROS 2 message type for headers
+
+# Predefined angles for the sensor's field of view
+ANGLES = [29.923, 22.515, 15.829, 8.964, 1.964, 188.964, 195.829, 202.515, 209.923]
+
+# Mapping of sensor keys to their translation and rotation data
+SENSOR_DATA = {
+    "sensor0": [[5], [1]], "sensor1": [[0], [1]], "sensor2": [[1], [1]],
+    "sensor3": [[1], [0]], "sensor4": [[0], [0]], "sensor5": [[5], [0]],
+    "sensor6": [[5], [-1]], "sensor7": [[0], [-1]], "sensor8": [[1], [-1]],
+    "sensor9": [[2], [-1]], "sensor10": [[3], [-1]], "sensor11": [[4], [-1]],
+    "sensor12": [[4], [0]], "sensor13": [[3], [0]], "sensor14": [[2], [0]],
+    "sensor15": [[2], [1]], "sensor16": [[3], [1]], "sensor17": [[4], [1]],
+}
+
+# Translation vector for the sensor in meters
+TRANSLATION_VECTOR = np.array([0.085, 0.06, 0])  # 85 mm in meters
+
+
+class SerialListPublisher(Node):
+    """
+    A ROS 2 node that reads data from a serial port, processes it, and publishes it as a PointCloud2 message.
+    """
+    def __init__(self, serial_port='/dev/ttyACM0', baudrate=115200):
+        super().__init__('serial_list_publisher')  # Initialize the ROS 2 node with a name
+        self.declare_parameter('parent_frame', 'vl53l7cx_link')  # Declare a parameter for the parent frame
+        self.parent_frame = self.get_parameter('parent_frame').get_parameter_value().string_value  # Get the parameter value
+
+        # Create a publisher for PointCloud2 messages
+        self.pcd_publisher = self.create_publisher(PointCloud2, 'pcd', 10)
+
+        # Open the serial port for communication
+        self.serial_port = serial.Serial(serial_port, baudrate, timeout=None)
+        self.get_logger().info(f"Connected to {serial_port} at {baudrate} baud")  # Log the connection details
+
+        # Start reading data from the serial port and publishing it
+        self.read_serial_and_publish()
+
+    def read_serial_and_publish(self):
+        """
+        Continuously read data from the serial port, process it, and publish it as a PointCloud2 message.
+        """
+        try:
+            while rclpy.ok():  # Keep running while ROS 2 is active
+                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
+                    continue
+                points_all = []  # Initialize an empty list for points
+
+                # Replace the first value with a high number for invalid points (where the second value in the pair is not 5)
+                filtered_data = {}
+                for key, array in data.items():
+                    filtered_array = []
+                    for pair in array:
+                        if pair[1] not in [1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14]:
+                            filtered_array.append([99999])
+                        else:
+                            filtered_array.append([pair[0]])
+                    filtered_data[key] = filtered_array
+                # Process the data for each sensor and create a point cloud
+                points_all = []
+                for key, array in filtered_data.items():
+                    distances = [pair[0] for pair in array if len(pair) > 0]
+                    if len(distances) == 64:  # Ensure the array has exactly 64 elements
+                        reshaped_array = np.array(distances).reshape(8, 8)
+                        points_all.append(self.create_pcd_from_distance(reshaped_array, key))
+                points = None
+                points = np.vstack(points_all)  # Combine all points into a single array
+                pcd = self.create_point_cloud(points, self.parent_frame)  # Create a PointCloud2 message
+                self.pcd_publisher.publish(pcd)  # Publish the point cloud
+
+        except serial.SerialException as e:
+            self.get_logger().error(f"Serial error: {e}")  # Log serial communication errors
+        except KeyboardInterrupt:
+            self.get_logger().info("Shutting down...")  # Log when the node is stopped by the user
+        finally:
+            self.serial_port.close()  # Close the serial port when done
+
+    def parse_json(self, line):
+        """
+        Parse a JSON string from the serial port.
+        """
+        try:
+            data = json.loads(line)  # Parse the JSON string
+            if not isinstance(data, dict):  # Ensure the data is a dictionary
+                self.get_logger().info(f"Unexpected JSON format: {data}")
+                return None
+            return data
+        except json.JSONDecodeError as e:
+            self.get_logger().warn(f"JSON decode error: {e} | Line: {line}")  # Log JSON parsing errors
+            return None
+
+    def create_pcd_from_distance(self, distance, sensor_key):
+        """
+        Create a point cloud from distance data for a specific sensor.
+        """
+        x, y, z = self.calculate_coordinates(distance)  # Calculate the 3D coordinates
+        points_local = np.hstack((x, y, z)) / 1000  # Convert coordinates to meters
+
+        # Get the yaw and pitch angles for the sensor
+        yaw_deg, pitch_deg = self.get_sensor_angles(sensor_key)
+        points_local = self.apply_transformations(points_local, yaw_deg, pitch_deg, sensor_key)  # Apply transformations
+        return points_local
+
+    def calculate_coordinates(self, distance):
+        """
+        Calculate the 3D coordinates from distance data.
+        """
+        x, y, z = [], [], []
+        for j in range(distance.shape[1]):  # Iterate over columns
+            for i in range(distance.shape[0]):  # Iterate over rows
+                dist = distance[i, j]  # Get the distance value
+                z.append(dist * np.sin(np.radians(ANGLES[j])))  # Calculate z-coordinate
+                y.append(dist * np.sin(np.radians(ANGLES[i])))  # Calculate y-coordinate
+                x.append(dist)  # x-coordinate is the distance itself
+        return np.array(x).reshape(-1, 1), np.array(y).reshape(-1, 1), np.array(z).reshape(-1, 1)
+
+    def get_sensor_angles(self, sensor_key):
+        """
+        Get the yaw and pitch angles for a specific sensor.
+        """
+        yaw_deg = SENSOR_DATA[sensor_key][1][0] * 60  # Calculate yaw angle
+        pitch_deg = SENSOR_DATA[sensor_key][0][0] * 60  # Calculate pitch angle
+        return yaw_deg, pitch_deg
+
+    def apply_transformations(self, points, yaw_deg, pitch_deg, sensor_key):
+        """
+        Apply rotation and translation transformations to the points.
+        """
+        yaw_rad, pitch_rad = np.radians([yaw_deg, pitch_deg])  # Convert angles to radians
+
+        # Rotation matrices for x, y, and z axes
+        Rx = self.rotation_matrix_x(-np.pi / 2)
+        Ry = self.rotation_matrix_y(yaw_rad)
+        Rz = self.rotation_matrix_z(pitch_rad)
+
+        # Apply the rotations
+        points = (Rx @ points.T).T
+        points = (Ry @ points.T).T
+        points = (Rz @ points.T).T
+
+        # Calculate the translation vector
+        translation = self.calculate_translation(yaw_rad, pitch_rad, sensor_key)
+        return points + translation  # Apply the translation
+
+    @staticmethod
+    def rotation_matrix_x(angle):
+        """
+        Create a rotation matrix for rotation around the x-axis.
+        """
+        return np.array([
+            [1, 0, 0],
+            [0, np.cos(angle), -np.sin(angle)],
+            [0, np.sin(angle), np.cos(angle)]
+        ])
+
+    @staticmethod
+    def rotation_matrix_y(angle):
+        """
+        Create a rotation matrix for rotation around the y-axis.
+        """
+        return np.array([
+            [np.cos(angle), 0, np.sin(angle)],
+            [0, 1, 0],
+            [-np.sin(angle), 0, np.cos(angle)]
+        ])
+
+    @staticmethod
+    def rotation_matrix_z(angle):
+        """
+        Create a rotation matrix for rotation around the z-axis.
+        """
+        return np.array([
+            [np.cos(angle), -np.sin(angle), 0],
+            [np.sin(angle), np.cos(angle), 0],
+            [0, 0, 1]
+        ])
+
+    def calculate_translation(self, yaw_rad, pitch_rad, sensor_key):
+        """
+        Calculate the translation vector based on yaw and pitch angles for specific sensors.
+        Only sensors with a 0 in the second list from SENSOR_DATA are moved.
+        """
+        if SENSOR_DATA[sensor_key][1][0] == 0:  # Check if the second list contains a 0
+            tx = TRANSLATION_VECTOR[0] * np.cos(pitch_rad) # x-component of translation
+            ty = TRANSLATION_VECTOR[0] * np.sin(pitch_rad)  # y-component of translation
+            tz = 0
+            return np.array([tx, ty, tz])  # Return the translation vector
+        if SENSOR_DATA[sensor_key][1][0] == 1:
+            tx = TRANSLATION_VECTOR[1] * np.cos(pitch_rad)
+            ty = TRANSLATION_VECTOR[1] * np.sin(pitch_rad)
+            tz = -(TRANSLATION_VECTOR[1] * np.cos(yaw_rad))  # z-component of translation
+            return np.array([tx, ty, tz])
+        if SENSOR_DATA[sensor_key][1][0] == -1:
+            tx = TRANSLATION_VECTOR[1] * np.cos(pitch_rad)
+            ty = TRANSLATION_VECTOR[1] * np.sin(pitch_rad)
+            tz = (TRANSLATION_VECTOR[1] * np.cos(yaw_rad))
+            return np.array([tx, ty, tz])
+        else:
+            return np.array([0, 0, 0])  # No translation for other sensors
+
+    def distance_filter(self, points, threshold):
+        """
+        Filter points based on a distance threshold.
+        """
+        mask = np.linalg.norm(points, axis=1) < threshold
+        return points[mask]  # Return only the points within the threshold
+
+    def create_point_cloud(self, points, parent_frame):
+        """
+        Create a PointCloud2 message from the 3D points.
+        """
+        ros_dtype = PointField.FLOAT32  # ROS 2 data type for floating-point numbers
+        dtype = np.float32  # NumPy data type for floating-point numbers
+        itemsize = np.dtype(dtype).itemsize  # Size of each data item in bytes
+        
+        data = points.astype(dtype).tobytes()  # Convert points to binary data
+
+        fields = [PointField(name=n, offset=i * itemsize, datatype=ros_dtype, count=1)
+                  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
+        return PointCloud2(
+            header=header,
+            height=1,  # Single row of points
+            width=points.shape[0],  # Number of points
+            is_dense=True,  # Allow for invalid points
+            is_bigendian=False,  # Data is in little-endian format
+            fields=fields,  # Fields for x, y, and z
+            point_step=(itemsize * 3),  # Size of each point in bytes
+            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):
+    """
+    Main function to initialize and run the ROS 2 node.
+    """
+    rclpy.init(args=args)  # Initialize the ROS 2 Python client library
+    node = SerialListPublisher(serial_port='/dev/ttyACM0', baudrate=115200)  # Create the node
+    try:
+        rclpy.spin(node)  # Keep the node running
+    except KeyboardInterrupt:
+        node.get_logger().info("Node stopped by user.")  # Log when the node is stopped
+    finally:
+        node.destroy_node()  # Destroy the node
+        rclpy.shutdown()  # Shut down the ROS 2 client library
+
+
+if __name__ == '__main__':
+    main()  # Run the main function
diff --git a/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/test_transform.py b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/test_transform.py
new file mode 100644
index 0000000000000000000000000000000000000000..4277d0d8936e38e024e00e4495ebe17519932360
--- /dev/null
+++ b/workspaces/COLCON_WS/src/serial_to_pcl/serial_to_pcl/test_transform.py
@@ -0,0 +1,139 @@
+import rclpy
+from rclpy.node import Node
+from sensor_msgs.msg import PointCloud2
+from tf2_ros import TransformListener, Buffer
+import numpy as np
+import trimesh
+from std_msgs.msg import Header
+# Removed unused import
+import os
+
+# Removed unused import
+import sensor_msgs.msg as sensor_msgs
+import sensor_msgs_py.point_cloud2 as pc2
+
+class PointCloudProcessor(Node):
+    def __init__(self):
+        super().__init__('pointcloud_processor')
+        self.subscription = self.create_subscription(
+            PointCloud2,
+            'pcd',
+            self.pointcloud_callback,
+            10)
+        self.publisher_valid = self.create_publisher(PointCloud2, '/valid_from_perspective', 10)
+        self.publisher_invalid = self.create_publisher(PointCloud2, '/invalid_from_perspective', 10)
+
+        self.tf_buffer = Buffer()
+        self.tf_listener = TransformListener(self.tf_buffer, self)
+
+        base_path = os.path.join(os.path.expanduser('~'), 'robot-sensor', 'workspaces', 'COLCON_WS', 'src', 'ur_description', 'meshes', 'ur10', 'collision_custom')
+        self.meshes_static = [
+            trimesh.load_mesh(os.path.join(base_path, 'shoulder.stl')),
+            trimesh.load_mesh(os.path.join(base_path, 'forearm.stl')),
+            trimesh.load_mesh(os.path.join(base_path, 'upperarm.stl')),
+            trimesh.load_mesh(os.path.join(base_path, 'wrist1.stl')),
+            trimesh.load_mesh(os.path.join(base_path, 'wrist2.stl')),
+            trimesh.load_mesh(os.path.join(base_path, 'wrist3.stl'))
+        ]
+
+        base_path_collision = os.path.join(os.path.expanduser('~'), 'robot-sensor', 'workspaces', 'COLCON_WS', 'src', 'ur_description', 'meshes', 'ur10', 'collision')
+        self.meshes_static.append(trimesh.load_mesh(os.path.join(base_path_collision, 'base.stl')))
+
+        scale_factor = 1.5
+        scale_matrix = trimesh.transformations.scale_matrix(scale_factor)
+        for mesh in self.meshes_static:
+            mesh.apply_transform(scale_matrix)
+
+    def visualize_meshes(self, meshes):
+        if meshes:  # Check if there are meshes to visualize
+            scene = trimesh.Scene()
+            for mesh in meshes:
+                scene.add_geometry(mesh)
+            scene.show()
+        else:
+            self.get_logger().info('No meshes to visualize.')
+
+    def pointcloud_callback(self, msg):
+        self.perspective_frame = 'vl53l7cx_link'
+        try:
+            now = rclpy.time.Time()
+            transforms = {
+                'base': self.tf_buffer.lookup_transform(self.perspective_frame, 'world', now),
+                'shoulder': self.tf_buffer.lookup_transform(self.perspective_frame, 'shoulder_link', now),
+                'upperarm': self.tf_buffer.lookup_transform(self.perspective_frame, 'upper_arm_link', now),
+                'forearm': self.tf_buffer.lookup_transform(self.perspective_frame, 'forearm_link', now),
+                'wrist1': self.tf_buffer.lookup_transform(self.perspective_frame, 'wrist_1_link', now),
+                'wrist2': self.tf_buffer.lookup_transform(self.perspective_frame, 'wrist_2_link', now),
+                'wrist3': self.tf_buffer.lookup_transform(self.perspective_frame, 'wrist_3_link', now)
+            }
+        except Exception as e:
+            self.get_logger().error(f'Error in looking up transform: {e}')
+        transformed_meshes = []
+        for i, transform in enumerate(transforms.values()):  # Removed unused 'key'
+            transformed_meshes.append(self.transform_mesh(transform, self.meshes_static[i]))
+        for i, (key, transform) in enumerate(transforms.items()):
+            transformed_meshes.append(self.transform_mesh(transform, self.meshes_static[i]))
+
+        translation_matrix_forearm = trimesh.transformations.translation_matrix([0, 0, -0.05])
+        transformed_meshes[3].apply_transform(translation_matrix_forearm)
+
+        self.visualize_meshes(transformed_meshes)
+
+        points = np.array([(point['x'], point['y'], point['z']) for point in pc2.read_points(msg, field_names=("x", "y", "z"), skip_nans=True)], dtype=np.float64)
+
+        inside_robot = np.logical_or.reduce([mesh.contains(points) for mesh in transformed_meshes])
+        outside_robot = np.logical_not(inside_robot)
+
+        points_outside_robot = points[outside_robot]
+        points_inside_robot = points[inside_robot]
+
+        self.publish_point_cloud(points_outside_robot, points_inside_robot)
+        self.get_logger().info(f'Number of points outside robot: {len(points_outside_robot)}')
+        self.get_logger().info(f'Number of points inside robot: {len(points_inside_robot)}')
+
+    def transform_mesh(self, transform, mesh_static):
+        translation = transform.transform.translation
+        rotation = transform.transform.rotation
+
+        translation_matrix = trimesh.transformations.translation_matrix([translation.x, translation.y, translation.z])
+        rotation_matrix = trimesh.transformations.quaternion_matrix([rotation.w, rotation.x, rotation.y, rotation.z])
+        transformation_matrix = np.dot(translation_matrix, rotation_matrix)
+
+        transformed_mesh = mesh_static.copy()
+        transformed_mesh.apply_transform(transformation_matrix)
+        return transformed_mesh
+
+    def publish_point_cloud(self, points_valid, points_invalid):
+        self.publisher_valid.publish(self.point_cloud(points_valid, self.perspective_frame))
+        self.publisher_invalid.publish(self.point_cloud(points_invalid, self.perspective_frame))
+
+    def point_cloud(self, points, parent_frame):
+        ros_dtype = sensor_msgs.PointField.FLOAT32
+        dtype = np.float32
+        itemsize = np.dtype(dtype).itemsize
+
+        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)
+
+        return sensor_msgs.PointCloud2(
+            header=header,
+            height=1,
+            width=points.shape[0],
+            is_dense=False,
+            is_bigendian=False,
+            fields=fields,
+            point_step=(itemsize * 3),
+            row_step=(itemsize * 3 * points.shape[0]),
+            data=data
+        )
+
+def main(args=None):
+    rclpy.init(args=args)
+    pointcloud_processor = PointCloudProcessor()
+    rclpy.spin(pointcloud_processor)
+    pointcloud_processor.destroy_node()
+    rclpy.shutdown()
+
+if __name__ == '__main__':
+    main()
\ No newline at end of file
diff --git a/workspaces/COLCON_WS/src/ser_test/setup.py b/workspaces/COLCON_WS/src/serial_to_pcl/setup.py
old mode 100644
new mode 100755
similarity index 61%
rename from workspaces/COLCON_WS/src/ser_test/setup.py
rename to workspaces/COLCON_WS/src/serial_to_pcl/setup.py
index f60ad645fde3d50ff777fa64686b3646da55bcd7..621d049a65dc8fd17e70cfabeb1b12c54b92dc9f
--- a/workspaces/COLCON_WS/src/ser_test/setup.py
+++ b/workspaces/COLCON_WS/src/serial_to_pcl/setup.py
@@ -1,6 +1,6 @@
 from setuptools import find_packages, setup
 
-package_name = 'ser_test'
+package_name = 'serial_to_pcl'
 
 setup(
     name=package_name,
@@ -15,14 +15,14 @@ setup(
     zip_safe=True,
     maintainer='sochi',
     maintainer_email='hj703144@igmr.rwth-aachen.de',
-    description='TODO: Package description',
-    license='TODO: License declaration',
+    description='Reads data from serial and converts it to a PointCloud2 message.',
+    license='MIT',
     tests_require=['pytest'],
     entry_points={
         'console_scripts': [
-            'ser_test_node = ser_test.ser_test_node:main',
-            'pcl_rob_node = ser_test.pcl_rob_node:main',
-            'pcl_rob_v2_node = ser_test.pcl_rob_v2_node:main',
+            'serial_to_pcl_node = serial_to_pcl.serial_to_pcl_node:main',
+            'pcl_rob_node = serial_to_pcl.pcl_rob_node:main',
+            'pcl_rob_v2_node = serial_to_pcl.pcl_rob_v2_node:main',
         ],
     },
 )
diff --git a/workspaces/COLCON_WS/src/ur_description/config/ur10/joint_limits.yaml b/workspaces/COLCON_WS/src/ur_description/config/ur10/joint_limits.yaml
index 91e633f4f34c555a5509d3926e4f57666fb112cf..5fb9c52ac03328b324e6082eedc29c17f36ea292 100644
--- a/workspaces/COLCON_WS/src/ur_description/config/ur10/joint_limits.yaml
+++ b/workspaces/COLCON_WS/src/ur_description/config/ur10/joint_limits.yaml
@@ -51,9 +51,9 @@ joint_limits:
   sensor_joint:
     # acceleration limits are not publicly available
     has_acceleration_limits: false
-    has_effort_limits: true
-    has_position_limits: true
-    has_velocity_limits: true
+    has_effort_limits: false
+    has_position_limits: false
+    has_velocity_limits: false
     max_effort: 0.0
     max_position: !degrees  0.0
     max_velocity: !degrees  0.0
diff --git a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/base.stl b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/base.stl
new file mode 100644
index 0000000000000000000000000000000000000000..16575ddf171310cb14bb9f5156572cbf45d2f4ca
Binary files /dev/null and b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/base.stl differ
diff --git a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/forearm.stl b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/forearm.stl
index 8a8c92bf3ec090782b8dbacdb929000377c4b739..d9ca04182997fe98d44ef328aec7442c79173adf 100644
Binary files a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/forearm.stl and b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/forearm.stl differ
diff --git a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/shoulder.stl b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/shoulder.stl
index ec94850e5cc31d7fe2d40d2057953118535fd9ca..7881e85c6e5b808e580fd53fa214d3a03f7e30ae 100644
Binary files a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/shoulder.stl and b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/shoulder.stl differ
diff --git a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/upperarm.stl b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/upperarm.stl
index 5c958dadc81a397047e1c4896dc4c5831fbad386..15af610fee9bd63c078b8e1ace9c0924d3e7457d 100644
Binary files a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/upperarm.stl and b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/upperarm.stl differ
diff --git a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/wrist1.stl b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/wrist1.stl
index 619c47feface2765b465d6bd2e14eef923446143..c9fa25520817f5a5066d6da8d158626b38033e9d 100644
Binary files a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/wrist1.stl and b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/wrist1.stl differ
diff --git a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/wrist2.stl b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/wrist2.stl
index a6a3a042de564330a574dadbb7ded6fa4b0b07c4..d3828547dee073927ca689de604a190f806b217a 100644
Binary files a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/wrist2.stl and b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/wrist2.stl differ
diff --git a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/wrist3.stl b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/wrist3.stl
index 7e38565bf0d016484b582b981c01353e36454518..597433627d5463c546b3f1d3f23c15f62da6ecb5 100644
Binary files a/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/wrist3.stl and b/workspaces/COLCON_WS/src/ur_description/meshes/ur10/collision_custom/wrist3.stl differ
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/LICENSE b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/LICENSE
deleted file mode 100644
index 812621108aaddaaaea8a783c3fc493a0e5e2114c..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/LICENSE
+++ /dev/null
@@ -1,21 +0,0 @@
-MIT License
-
-Copyright (c) 2020 Sebastian Grans
-
-Permission is hereby granted, free of charge, to any person obtaining a copy
-of this software and associated documentation files (the "Software"), to deal
-in the Software without restriction, including without limitation the rights
-to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
-copies of the Software, and to permit persons to whom the Software is
-furnished to do so, subject to the following conditions:
-
-The above copyright notice and this permission notice shall be included in all
-copies or substantial portions of the Software.
-
-THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
-IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
-FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
-AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
-LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
-OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
-SOFTWARE.
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/README.md b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/README.md
deleted file mode 100644
index 75878ac1a613d48f5d7eeb38be48353fd11a1c55..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/README.md
+++ /dev/null
@@ -1,81 +0,0 @@
-# ROS2 Point Cloud 
-
-![](demo.gif)
-
-
-This is an example ROS2 (python) package which demonstrates how to utilize the `sensor_msg.msg.PointCloud2`. The various scripts show how to publish a point cloud represented by a `numpy` array as a `PointCloud2` message, and vice versa. I also demonstrate how to visualize a point cloud in RViz2.
-
-**Note:** This was initially posted on [SebastianGrans.github.io](http://sebastiangrans.github.io), but this is the more recent version.
-
-**This is now updated to work on ROS2 Galactic**  
-
-## Installation
-
-Move to your ROS workspace source folder, e.g:
-```
-cd ~/dev_ws/src
-```
-Clone this repo:
-```
-git clone https://github.com/SebastianGrans/ROS2-Point-Cloud-Demo.git
-```
-Compile:
-```
-cd ~/dev_ws/
-source /opt/ros/galactic/setup.sh
-colcon build --symlink-install --packages-select pcd_demo
-source install/
-```
-
-## Running
-Source the installation:
-```
-cd ~/dev_ws/
-source install/local_setup.sh # If you use bash
-# _or_
-source install/local_setup.zsh # If you use zsh
-```
-
-
-### Publisher demo
-#### Using a launch file (automatically starts RViz)
-```
-ros2 launch pcd_demo pcd_publisher_demo.launch.py
-```
-RViz should now show a spinning Utah teapot! 
-
-#### Manually
-
-```
-ros2 run pcd_demo pcd_publisher_node ~/dev_ws/src/ROS2-Point-Cloud-Demo/resource/teapot.ply    
-```
-In a new terminal:
-```
-ros2 run rviz2 rviz2
-```
-Make sure the `Displays` panel is visible `Panels > [✔] Displays`. Then, in the lower corner, press `Add` and select `PointCloud2`. In the list, expand `PointCloud2` and specify `pcd` as the topic. 
-
-RViz should now show a spinning Utah teapot! 
-
-### Subscriber demo
-This demo is similar to the one above, but rather than relying on RViz, we instead use [Open3D](http://www.open3d.org/) for visualization. 
-
-**Note:** This is not yet fully optimized. It needs to be threaded such that the Open3D interface is responsive. 
-
-#### Running from launch file
-
-```
-ros2 launch pcd_demo pcd_pubsub_demo.launch.py
-```
-
-#### Manually
-
-In one terminal, run the publisher:
-```
-ros2 run pcd_demo pcd_publisher_node ~/dev_ws/src/pcd_publisher/resource/teapot.ply    
-```
-and in another terminal, run the subscriber node:
-```
-ros2 run pcd_demo pcd_subscriber_node
-```
-
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/config/config.rviz b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/config/config.rviz
deleted file mode 100644
index 2dba7fa11475ad2db0a82a8a305d84a5b8d55a57..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/config/config.rviz
+++ /dev/null
@@ -1,159 +0,0 @@
-Panels:
-  - Class: rviz_common/Displays
-    Help Height: 78
-    Name: Displays
-    Property Tree Widget:
-      Expanded:
-        - /Global Options1
-        - /Status1
-        - /Grid1
-        - /PointCloud21
-        - /PointCloud21/Topic1
-      Splitter Ratio: 0.5
-    Tree Height: 903
-  - Class: rviz_common/Selection
-    Name: Selection
-  - Class: rviz_common/Tool Properties
-    Expanded:
-      - /2D Goal Pose1
-      - /Publish Point1
-    Name: Tool Properties
-    Splitter Ratio: 0.5886790156364441
-  - Class: rviz_common/Views
-    Expanded:
-      - /Current View1
-    Name: Views
-    Splitter Ratio: 0.5
-Visualization Manager:
-  Class: ""
-  Displays:
-    - Alpha: 0.5
-      Cell Size: 1
-      Class: rviz_default_plugins/Grid
-      Color: 160; 160; 164
-      Enabled: true
-      Line Style:
-        Line Width: 0.029999999329447746
-        Value: Lines
-      Name: Grid
-      Normal Cell Count: 0
-      Offset:
-        X: 0
-        Y: 0
-        Z: 0
-      Plane: XY
-      Plane Cell Count: 10
-      Reference Frame: <Fixed Frame>
-      Value: true
-    - Alpha: 1
-      Autocompute Intensity Bounds: true
-      Autocompute Value Bounds:
-        Max Value: 3.1500000953674316
-        Min Value: 0
-        Value: true
-      Axis: Z
-      Channel Name: intensity
-      Class: rviz_default_plugins/PointCloud2
-      Color: 255; 255; 255
-      Color Transformer: AxisColor
-      Decay Time: 0
-      Enabled: true
-      Invert Rainbow: false
-      Max Color: 255; 255; 255
-      Max Intensity: 4096
-      Min Color: 0; 0; 0
-      Min Intensity: 0
-      Name: PointCloud2
-      Position Transformer: XYZ
-      Selectable: true
-      Size (Pixels): 4
-      Size (m): 0.009999999776482582
-      Style: Points
-      Topic:
-        Depth: 5
-        Durability Policy: Volatile
-        History Policy: Keep Last
-        Reliability Policy: Reliable
-        Value: pcd
-      Use Fixed Frame: true
-      Use rainbow: true
-      Value: true
-  Enabled: true
-  Global Options:
-    Background Color: 48; 48; 48
-    Fixed Frame: map
-    Frame Rate: 30
-  Name: root
-  Tools:
-    - Class: rviz_default_plugins/Interact
-      Hide Inactive Objects: true
-    - Class: rviz_default_plugins/MoveCamera
-    - Class: rviz_default_plugins/Select
-    - Class: rviz_default_plugins/FocusCamera
-    - Class: rviz_default_plugins/Measure
-      Line color: 128; 128; 0
-    - Class: rviz_default_plugins/SetInitialPose
-      Topic:
-        Depth: 5
-        Durability Policy: Volatile
-        History Policy: Keep Last
-        Reliability Policy: Reliable
-        Value: /initialpose
-    - Class: rviz_default_plugins/SetGoal
-      Topic:
-        Depth: 5
-        Durability Policy: Volatile
-        History Policy: Keep Last
-        Reliability Policy: Reliable
-        Value: /goal_pose
-    - Class: rviz_default_plugins/PublishPoint
-      Single click: true
-      Topic:
-        Depth: 5
-        Durability Policy: Volatile
-        History Policy: Keep Last
-        Reliability Policy: Reliable
-        Value: /clicked_point
-  Transformation:
-    Current:
-      Class: rviz_default_plugins/TF
-  Value: true
-  Views:
-    Current:
-      Class: rviz_default_plugins/Orbit
-      Distance: 11.848302841186523
-      Enable Stereo Rendering:
-        Stereo Eye Separation: 0.05999999865889549
-        Stereo Focal Distance: 1
-        Swap Stereo Eyes: false
-        Value: false
-      Focal Point:
-        X: -0.3050713837146759
-        Y: -0.500482439994812
-        Z: 0.7005792260169983
-      Focal Shape Fixed Size: true
-      Focal Shape Size: 0.05000000074505806
-      Invert Z Axis: false
-      Name: Current View
-      Near Clip Distance: 0.009999999776482582
-      Pitch: 0.5153985023498535
-      Target Frame: <Fixed Frame>
-      Value: Orbit (rviz)
-      Yaw: 1.8503971099853516
-    Saved: ~
-Window Geometry:
-  Displays:
-    collapsed: false
-  Height: 1132
-  Hide Left Dock: false
-  Hide Right Dock: false
-  QMainWindow State: 000000ff00000000fd0000000400000000000001af00000412fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d00000412000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f00000412fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d00000412000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004420000003efc0100000002fb0000000800540069006d00650100000000000004420000000000000000fb0000000800540069006d00650100000000000004500000000000000000000004ce0000041200000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
-  Selection:
-    collapsed: false
-  Tool Properties:
-    collapsed: false
-  Views:
-    collapsed: false
-  Width: 1944
-  X: 292
-  Y: 297
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/launch/pcd_publisher_demo.launch.py b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/launch/pcd_publisher_demo.launch.py
deleted file mode 100644
index 8ea24e8aae982b43718b934965cc171c397eae6f..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/launch/pcd_publisher_demo.launch.py
+++ /dev/null
@@ -1,31 +0,0 @@
-import os
-
-from ament_index_python.packages import get_package_share_directory
-from launch import LaunchDescription
-from launch_ros.actions import Node
-
-def generate_launch_description():
-
-    rviz_config_dir = os.path.join(get_package_share_directory(
-        'pcd_demo'), 'config', 'config.rviz')
-    assert os.path.exists(rviz_config_dir)
-
-    ply_path = os.path.join(get_package_share_directory(
-        'pcd_demo'), 'resource', 'teapot.ply')
-    assert os.path.exists(ply_path)
-
-    return LaunchDescription([
-        Node(package='rviz2',
-            executable='rviz2',
-            name='rviz2',
-            arguments=['-d', rviz_config_dir],
-            output='screen'
-        ),
-        Node(package='pcd_demo',
-            executable='pcd_publisher_node',
-            name='pcd_publisher_node',
-            output='screen',
-            arguments=[ply_path],
-        ),
-    ])
-
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/launch/pcd_pubsub_demo.launch.py b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/launch/pcd_pubsub_demo.launch.py
deleted file mode 100644
index 2c8adf978c2632b5171294b65fe278621faf7bdd..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/launch/pcd_pubsub_demo.launch.py
+++ /dev/null
@@ -1,27 +0,0 @@
-import os
-
-from ament_index_python.packages import get_package_share_directory
-from launch import LaunchDescription
-from launch_ros.actions import Node
-
-def generate_launch_description():
-
-
-    ply_path = os.path.join(get_package_share_directory(
-        'pcd_demo'), 'resource', 'teapot.ply')
-    assert os.path.exists(ply_path)
-
-    return LaunchDescription([
-        Node(package='pcd_demo',
-            executable='pcd_publisher_node',
-            name='pcd_publisher_node',
-            output='screen',
-            arguments=[ply_path],
-        ),
-        Node(package='pcd_demo',
-            executable='pcd_subscriber_node',
-            name='pcd_subscriber_node',
-            output='screen',
-            arguments=[ply_path],
-        ),
-    ])
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/package.xml b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/package.xml
deleted file mode 100644
index 7d8238439345f4e5f65c022019c99a1ac25adbc8..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/package.xml
+++ /dev/null
@@ -1,24 +0,0 @@
-<?xml version="1.0"?>
-<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
-<package format="3">
-  <name>pcd_demo</name>
-  <version>0.0.1</version>
-  <description>Demo on how to utilize the sensor_msgs::msg::PointCloud2 message type in ROS2, RViz2 and numpy.</description>
-  <maintainer email="sebastian.grans@ntnu.no">Sebastian Grans</maintainer>
-  <license>MIT License</license>
-
-
-  <exec_depend>rclpy</exec_depend>
-  <exec_depend>ros2launch</exec_depend>
-  <exec_depend>std_msgs</exec_depend>
-  <exec_depend>sensor_msgs</exec_depend>
-
-  <test_depend>ament_copyright</test_depend>
-  <test_depend>ament_flake8</test_depend>
-  <test_depend>ament_pep257</test_depend>
-  <test_depend>python3-pytest</test_depend>
-
-  <export>
-    <build_type>ament_python</build_type>
-  </export>
-</package>
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_publisher/pcd_publisher_node copy.py b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_publisher/pcd_publisher_node copy.py
deleted file mode 100644
index 7b86d713011a3b575371f59f86ce215795b9447a..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_publisher/pcd_publisher_node copy.py	
+++ /dev/null
@@ -1,118 +0,0 @@
-
-import sys
-import os
-
-import rclpy 
-from rclpy.node import Node
-import sensor_msgs.msg as sensor_msgs
-import std_msgs.msg as std_msgs
-
-import numpy as np
-import open3d as o3d
-
-class PCDPublisher(Node):
-
-    def __init__(self):
-        super().__init__('pcd_publisher_node')
-
-        # This executable expectes the first argument to be the path to a 
-        # point cloud file. I.e. when you run it with ros:
-        # ros2 run pcd_publisher pcd_publisher_node /path/to/ply
-        assert len(sys.argv) > 1, "No ply file given."
-        assert os.path.exists(sys.argv[1]), "File doesn't exist."
-        pcd_path = sys.argv[1]
-
-        # I use Open3D to read point clouds and meshes. It's a great library!
-        pcd = o3d.io.read_point_cloud(pcd_path)
-        # I then convert it into a numpy array.
-        self.points = np.asarray(pcd.points)
-        print(self.points.shape)
-        
-        # I create a publisher that publishes sensor_msgs.PointCloud2 to the 
-        # topic 'pcd'. The value '10' refers to the history_depth, which I 
-        # believe is related to the ROS1 concept of queue size. 
-        # Read more here: 
-        # http://wiki.ros.org/rospy/Overview/Publishers%20and%20Subscribers
-        self.pcd_publisher = self.create_publisher(sensor_msgs.PointCloud2, 'pcd', 10)
-        timer_period = 1/30.0
-        self.timer = self.create_timer(timer_period, self.timer_callback)
-
-        # This rotation matrix is used for visualization purposes. It rotates
-        # the point cloud on each timer callback. 
-        self.R = o3d.geometry.get_rotation_matrix_from_xyz([0, 0, np.pi/48])
-
-              
-                
-    def timer_callback(self):
-        # For visualization purposes, I rotate the point cloud with self.R 
-        # to make it spin. 
-        # Here I use the point_cloud() function to convert the numpy array 
-        # into a sensor_msgs.PointCloud2 object. The second argument is the 
-        # name of the frame the point cloud will be represented in. The default
-        # (fixed) frame in RViz is called 'map'
-        self.pcd = point_cloud(self.points, 'map')
-        # Then I publish the PointCloud2 object 
-        self.pcd_publisher.publish(self.pcd)
-
-def point_cloud(points, parent_frame):
-    """ Creates a point cloud message.
-    Args:
-        points: Nx3 array of xyz positions.
-        parent_frame: frame in which the point cloud is defined
-    Returns:
-        sensor_msgs/PointCloud2 message
-
-    Code source:
-        https://gist.github.com/pgorczak/5c717baa44479fa064eb8d33ea4587e0
-
-    References:
-        http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html
-        http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointField.html
-        http://docs.ros.org/melodic/api/std_msgs/html/msg/Header.html
-
-    """
-    # In a PointCloud2 message, the point cloud is stored as an byte 
-    # array. In order to unpack it, we also include some parameters 
-    # which desribes the size of each individual point.
-    ros_dtype = sensor_msgs.PointField.FLOAT32
-    dtype = np.float32
-    itemsize = np.dtype(dtype).itemsize # A 32-bit float takes 4 bytes.
-
-    data = points.astype(dtype).tobytes() 
-
-    # The fields specify what the bytes represents. The first 4 bytes 
-    # represents the x-coordinate, the next 4 the y-coordinate, etc.
-    fields = [sensor_msgs.PointField(
-        name=n, offset=i*itemsize, datatype=ros_dtype, count=1)
-        for i, n in enumerate('xyz')]
-
-    # The PointCloud2 message also has a header which specifies which 
-    # coordinate frame it is represented in. 
-    header = std_msgs.Header(frame_id=parent_frame)
-
-    return sensor_msgs.PointCloud2(
-        header=header,
-        height=1, 
-        width=points.shape[0],
-        is_dense=False,
-        is_bigendian=False,
-        fields=fields,
-        point_step=(itemsize * 3), # Every point consists of three float32s.
-        row_step=(itemsize * 3 * points.shape[0]),
-        data=data
-    )
-
-def main(args=None):
-    # Boilerplate code.
-    rclpy.init(args=args)
-    pcd_publisher = PCDPublisher()
-    rclpy.spin(pcd_publisher)
-    
-    # Destroy the node explicitly
-    # (optional - otherwise it will be done automatically
-    # when the garbage collector destroys the node object)
-    pcd_publisher.destroy_node()
-    rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_publisher/pcd_publisher_node.py b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_publisher/pcd_publisher_node.py
deleted file mode 100644
index 5c4a0c13291d042dfbd942274f1b44ac66a1b13b..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_publisher/pcd_publisher_node.py
+++ /dev/null
@@ -1,119 +0,0 @@
-
-import sys
-import os
-
-import rclpy 
-from rclpy.node import Node
-import sensor_msgs.msg as sensor_msgs
-import std_msgs.msg as std_msgs
-
-import numpy as np
-import open3d as o3d
-
-class PCDPublisher(Node):
-
-    def __init__(self):
-        super().__init__('pcd_publisher_node')
-
-        # This executable expectes the first argument to be the path to a 
-        # point cloud file. I.e. when you run it with ros:
-        # ros2 run pcd_publisher pcd_publisher_node /path/to/ply
-        assert len(sys.argv) > 1, "No ply file given."
-        assert os.path.exists(sys.argv[1]), "File doesn't exist."
-        pcd_path = sys.argv[1]
-
-        # I use Open3D to read point clouds and meshes. It's a great library!
-        pcd = o3d.io.read_point_cloud(pcd_path)
-        # I then convert it into a numpy array.
-        self.points = np.asarray(pcd.points)
-        print(self.points.shape)
-        
-        # I create a publisher that publishes sensor_msgs.PointCloud2 to the 
-        # topic 'pcd'. The value '10' refers to the history_depth, which I 
-        # believe is related to the ROS1 concept of queue size. 
-        # Read more here: 
-        # http://wiki.ros.org/rospy/Overview/Publishers%20and%20Subscribers
-        self.pcd_publisher = self.create_publisher(sensor_msgs.PointCloud2, 'pcd', 10)
-        timer_period = 1/30.0
-        self.timer = self.create_timer(timer_period, self.timer_callback)
-
-        # This rotation matrix is used for visualization purposes. It rotates
-        # the point cloud on each timer callback. 
-        self.R = o3d.geometry.get_rotation_matrix_from_xyz([0, 0, np.pi/48])
-
-              
-                
-    def timer_callback(self):
-        # For visualization purposes, I rotate the point cloud with self.R 
-        # to make it spin. 
-        self.points = self.points @ self.R
-        # Here I use the point_cloud() function to convert the numpy array 
-        # into a sensor_msgs.PointCloud2 object. The second argument is the 
-        # name of the frame the point cloud will be represented in. The default
-        # (fixed) frame in RViz is called 'map'
-        self.pcd = point_cloud(self.points, 'map')
-        # Then I publish the PointCloud2 object 
-        self.pcd_publisher.publish(self.pcd)
-
-def point_cloud(points, parent_frame):
-    """ Creates a point cloud message.
-    Args:
-        points: Nx3 array of xyz positions.
-        parent_frame: frame in which the point cloud is defined
-    Returns:
-        sensor_msgs/PointCloud2 message
-
-    Code source:
-        https://gist.github.com/pgorczak/5c717baa44479fa064eb8d33ea4587e0
-
-    References:
-        http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html
-        http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointField.html
-        http://docs.ros.org/melodic/api/std_msgs/html/msg/Header.html
-
-    """
-    # In a PointCloud2 message, the point cloud is stored as an byte 
-    # array. In order to unpack it, we also include some parameters 
-    # which desribes the size of each individual point.
-    ros_dtype = sensor_msgs.PointField.FLOAT32
-    dtype = np.float32
-    itemsize = np.dtype(dtype).itemsize # A 32-bit float takes 4 bytes.
-
-    data = points.astype(dtype).tobytes() 
-
-    # The fields specify what the bytes represents. The first 4 bytes 
-    # represents the x-coordinate, the next 4 the y-coordinate, etc.
-    fields = [sensor_msgs.PointField(
-        name=n, offset=i*itemsize, datatype=ros_dtype, count=1)
-        for i, n in enumerate('xyz')]
-
-    # The PointCloud2 message also has a header which specifies which 
-    # coordinate frame it is represented in. 
-    header = std_msgs.Header(frame_id=parent_frame)
-
-    return sensor_msgs.PointCloud2(
-        header=header,
-        height=1, 
-        width=points.shape[0],
-        is_dense=False,
-        is_bigendian=False,
-        fields=fields,
-        point_step=(itemsize * 3), # Every point consists of three float32s.
-        row_step=(itemsize * 3 * points.shape[0]),
-        data=data
-    )
-
-def main(args=None):
-    # Boilerplate code.
-    rclpy.init(args=args)
-    pcd_publisher = PCDPublisher()
-    rclpy.spin(pcd_publisher)
-    
-    # Destroy the node explicitly
-    # (optional - otherwise it will be done automatically
-    # when the garbage collector destroys the node object)
-    pcd_publisher.destroy_node()
-    rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_subscriber/pcd_subscriber_node.py b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_subscriber/pcd_subscriber_node.py
deleted file mode 100644
index eb5072bebf68ed56a7e1d3eb0bea80646a5160c6..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_subscriber/pcd_subscriber_node.py
+++ /dev/null
@@ -1,162 +0,0 @@
-import sys
-import os
-
-import rclpy 
-from rclpy.node import Node
-import sensor_msgs.msg as sensor_msgs
-
-
-import numpy as np
-import open3d as o3d
-
-class PCDListener(Node):
-
-    def __init__(self):
-        super().__init__('pcd_subsriber_node')
-
-        ## This is for visualization of the received point cloud.
-        self.vis = o3d.visualization.Visualizer()
-        self.vis.create_window()
-        self.o3d_pcd = o3d.geometry.PointCloud()
-
-        # Set up a subscription to the 'pcd' topic with a callback to the 
-        # function `listener_callback`
-        self.pcd_subscriber = self.create_subscription(
-            sensor_msgs.PointCloud2,    # Msg type
-            'pcd',                      # topic
-            self.listener_callback,      # Function to call
-            10                          # QoS
-        )
-
-                
-    def listener_callback(self, msg):
-        # Here we convert the 'msg', which is of the type PointCloud2.
-        # I ported the function read_points2 from 
-        # the ROS1 package. 
-        # https://github.com/ros/common_msgs/blob/noetic-devel/sensor_msgs/src/sensor_msgs/point_cloud2.py
-
-        pcd_as_numpy_array = np.array(list(read_points(msg)))
-        
-
-        # The rest here is for visualization.
-        self.vis.remove_geometry(self.o3d_pcd)
-        self.o3d_pcd = o3d.geometry.PointCloud(
-                            o3d.utility.Vector3dVector(pcd_as_numpy_array))
-
-        self.vis.add_geometry(self.o3d_pcd)
-
-        
-        
-        self.vis.poll_events()
-        self.vis.update_renderer()
-
-        
-
-
-## The code below is "ported" from 
-# https://github.com/ros/common_msgs/tree/noetic-devel/sensor_msgs/src/sensor_msgs
-import sys
-from collections import namedtuple
-import ctypes
-import math
-import struct
-from sensor_msgs.msg import PointCloud2, PointField
-
-_DATATYPES = {}
-_DATATYPES[PointField.INT8]    = ('b', 1)
-_DATATYPES[PointField.UINT8]   = ('B', 1)
-_DATATYPES[PointField.INT16]   = ('h', 2)
-_DATATYPES[PointField.UINT16]  = ('H', 2)
-_DATATYPES[PointField.INT32]   = ('i', 4)
-_DATATYPES[PointField.UINT32]  = ('I', 4)
-_DATATYPES[PointField.FLOAT32] = ('f', 4)
-_DATATYPES[PointField.FLOAT64] = ('d', 8)
-
-def read_points(cloud, field_names=None, skip_nans=False, uvs=[]):
-    """
-    Read points from a L{sensor_msgs.PointCloud2} message.
-
-    @param cloud: The point cloud to read from.
-    @type  cloud: L{sensor_msgs.PointCloud2}
-    @param field_names: The names of fields to read. If None, read all fields. [default: None]
-    @type  field_names: iterable
-    @param skip_nans: If True, then don't return any point with a NaN value.
-    @type  skip_nans: bool [default: False]
-    @param uvs: If specified, then only return the points at the given coordinates. [default: empty list]
-    @type  uvs: iterable
-    @return: Generator which yields a list of values for each point.
-    @rtype:  generator
-    """
-    assert isinstance(cloud, PointCloud2), 'cloud is not a sensor_msgs.msg.PointCloud2'
-    fmt = _get_struct_fmt(cloud.is_bigendian, cloud.fields, field_names)
-    width, height, point_step, row_step, data, isnan = cloud.width, cloud.height, cloud.point_step, cloud.row_step, cloud.data, math.isnan
-    unpack_from = struct.Struct(fmt).unpack_from
-
-    if skip_nans:
-        if uvs:
-            for u, v in uvs:
-                p = unpack_from(data, (row_step * v) + (point_step * u))
-                has_nan = False
-                for pv in p:
-                    if isnan(pv):
-                        has_nan = True
-                        break
-                if not has_nan:
-                    yield p
-        else:
-            for v in range(height):
-                offset = row_step * v
-                for u in range(width):
-                    p = unpack_from(data, offset)
-                    has_nan = False
-                    for pv in p:
-                        if isnan(pv):
-                            has_nan = True
-                            break
-                    if not has_nan:
-                        yield p
-                    offset += point_step
-    else:
-        if uvs:
-            for u, v in uvs:
-                yield unpack_from(data, (row_step * v) + (point_step * u))
-        else:
-            for v in range(height):
-                offset = row_step * v
-                for u in range(width):
-                    yield unpack_from(data, offset)
-                    offset += point_step
-
-def _get_struct_fmt(is_bigendian, fields, field_names=None):
-    fmt = '>' if is_bigendian else '<'
-
-    offset = 0
-    for field in (f for f in sorted(fields, key=lambda f: f.offset) if field_names is None or f.name in field_names):
-        if offset < field.offset:
-            fmt += 'x' * (field.offset - offset)
-            offset = field.offset
-        if field.datatype not in _DATATYPES:
-            print('Skipping unknown PointField datatype [%d]' % field.datatype, file=sys.stderr)
-        else:
-            datatype_fmt, datatype_length = _DATATYPES[field.datatype]
-            fmt    += field.count * datatype_fmt
-            offset += field.count * datatype_length
-
-    return fmt
-
-
-
-def main(args=None):
-    # Boilerplate code.
-    rclpy.init(args=args)
-    pcd_listener = PCDListener()
-    rclpy.spin(pcd_listener)
-    
-    # Destroy the node explicitly
-    # (optional - otherwise it will be done automatically
-    # when the garbage collector destroys the node object)
-    pcd_listener.destroy_node()
-    rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/ser_test/__init__.py b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/ser_test/__init__.py
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/ser_test/ser_test.py b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/ser_test/ser_test.py
deleted file mode 100644
index 59e4c6986dc4c1ec77d0b4205abcccd51ed4b581..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/ser_test/ser_test.py
+++ /dev/null
@@ -1,48 +0,0 @@
-import serial
-import rclpy
-from rclpy.node import Node
-from std_msgs.msg import String
-
-
-class SerialStringPublisher(Node):
-    def __init__(self, serial_port='/dev/ttyACM0', baudrate=115200):
-        super().__init__('serial_string_publisher')
-        self.publisher_ = self.create_publisher(String, 'serial_data', 10)
-        self.serial_port = serial.Serial(serial_port, baudrate, timeout=None)
-        self.get_logger().info(f"Connected to {serial_port} at {baudrate} baud")
-        self.read_serial_and_publish()
-
-    def read_serial_and_publish(self):
-        try:
-            while rclpy.ok():
-                # Read a line from the serial port
-                line = self.serial_port.readline().decode('utf-8').strip()
-                self.get_logger().info(f"Received: {line}")
-
-                # Publish the received line as a String message
-                msg = String()
-                msg.data = line
-                self.publisher_.publish(msg)
-
-        except serial.SerialException as e:
-            self.get_logger().error(f"Serial error: {e}")
-        except KeyboardInterrupt:
-            self.get_logger().info("Shutting down...")
-        finally:
-            self.serial_port.close()
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = SerialStringPublisher(serial_port='/dev/ttyACM0')
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        node.get_logger().info("Node stopped by user.")
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-
-if __name__ == '__main__':
-    main()
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/resource/bunny.ply b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/resource/bunny.ply
deleted file mode 100644
index d616380961a89bd204f547739ec94a7d2bc5c85f..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/resource/bunny.ply
+++ /dev/null
@@ -1,1413 +0,0 @@
-ply
-format ascii 1.0
-comment zipper output
-element vertex 453
-property float x
-property float y
-property float z
-property float confidence
-property float intensity
-element face 948
-property list uchar int vertex_indices
-end_header
--0.0312216 0.126304 0.00514924 0.850855 0.5 
--0.0446774 0.131204 0.00570479 0.900159 0.5 
--0.0683011 0.144828 0.0413688 0.398443 0.5 
--0.00600095 0.130398 0.0178986 0.85268 0.5 
--0.0173568 0.127613 0.00526885 0.675938 0.5 
-0.0330513 0.107034 0.0319543 0.652757 0.5 
-0.0400873 0.10521 0.0173419 0.708171 0.5 
--0.0301802 0.106322 0.0399745 0.454541 0.437538 
-0.0304193 0.118572 0.0188068 0.533079 0.5 
--0.0640822 0.159391 -0.0169096 0.404517 0.5 
-0.0447046 0.0927877 0.00507585 0.579563 0.425995 
--0.0316754 0.170395 -0.00635023 0.365607 0.5 
--0.0848523 0.134078 0.0470177 0.499575 0.5 
--0.0688547 0.122052 0.0517569 0.564827 0.5 
-0.00595475 0.131024 0.0178252 0.748371 0.5 
-0.0404629 0.105142 0.00640978 0.680399 0.5 
-0.0387342 0.102161 -0.00463112 0.600054 0.5 
--0.0914513 0.134136 0.0171026 0.824561 0.5 
--0.0818721 0.107166 0.031016 0.690889 0.5 
--0.067218 0.156155 0.0178863 0.807492 0.5 
--0.0795687 0.152875 0.0299311 0.248168 0.41865 
-0.00596007 0.122504 0.0346272 0.555044 0.354559 
--0.0516317 0.145001 0.0184804 0.691477 0.5 
--0.0779781 0.13255 0.0513494 0.566256 0.5 
--0.00590708 0.127934 0.0274623 0.271491 0.462815 
--0.0479133 0.129301 0.0269646 0.539149 0.5 
--0.082427 0.0928134 -0.00556046 0.710999 0.5 
-0.01744 0.127694 0.0185348 0.530957 0.5 
--0.0906868 0.120305 0.0066804 0.635593 0.5 
--0.0294038 0.17903 -0.00787959 0.269231 0.447035 
--0.0797891 0.14376 0.0426994 0.414139 0.5 
--0.018288 0.108329 0.0415098 0.482541 0.5 
--0.0202326 0.181846 -0.0183274 0.341071 0.440034 
--0.0377039 0.167987 -0.0130391 0.396317 0.473039 
-0.00582164 0.12806 0.0279016 0.350014 0.41288 
--0.0435389 0.130014 0.0175333 0.599596 0.5 
-0.0188699 0.119862 0.032409 0.625269 0.5 
--0.0440101 0.167035 0.00231898 0.413994 0.469929 
--0.089811 0.132401 0.00705743 0.625486 0.5 
--0.057352 0.144989 0.0315196 0.696873 0.5 
-0.0442622 0.0934526 0.0176417 0.665192 0.5 
-0.0412343 0.0921731 0.0285603 0.671611 0.5 
--0.0563953 0.154565 0.016878 0.394763 0.437313 
--0.0206135 0.159773 -0.00717522 0.136389 0.380194 
--0.0729893 0.0656116 0.0181693 0.413051 0.5 
--0.0673967 0.155256 0.00581389 0.855717 0.5 
--0.0904864 0.118611 0.0412148 0.673877 0.5 
-0.0273142 0.117965 0.0286191 0.635485 0.5 
-0.041907 0.0916386 -0.00556945 0.585857 0.459742 
--0.0702109 0.165303 -0.0194661 0.548789 0.5 
--0.0061847 0.122729 0.034787 0.602316 0.374044 
-0.0300138 0.0932786 0.0421476 0.649753 0.5 
--0.0175129 0.162126 -0.0145489 0.338176 0.5 
--0.0763977 0.171291 -0.0411021 0.256591 0.4298 
--0.0854227 0.105386 0.00339486 0.523819 0.297125 
-0.0370431 0.110443 0.0207229 0.52623 0.448558 
--0.00659732 0.0427285 0.0469391 0.280725 0.5 
-0.00639794 0.0437006 0.046826 0.331809 0.5 
--0.0559247 0.157606 0.00656455 0.561042 0.5 
--0.0911449 0.118816 0.0298442 0.848517 0.5 
--0.0595109 0.128352 0.0399626 0.658867 0.444043 
--0.0176335 0.127605 0.0179366 0.547632 0.5 
--0.066633 0.153831 0.0308703 0.855321 0.5 
--0.0436418 0.169438 -0.00550226 0.274377 0.177706 
--0.0572759 0.043243 0.042862 0.417977 0.459314 
--0.0763773 0.157221 -0.0168889 0.267801 0.372187 
--0.0434461 0.15605 0.00615795 0.447592 0.5 
--0.0427118 0.0421645 0.0427004 0.509262 0.5 
--0.0254201 0.0886622 0.0503827 0.608282 0.5 
--0.014179 0.12627 0.0266417 0.420759 0.5 
--0.0882582 0.0898687 0.00696625 0.753697 0.5 
--0.0688695 0.157773 -0.00687593 0.595216 0.5 
--0.0679676 0.142877 -0.00757643 0.446131 0.5 
-0.0188538 0.106293 0.0416902 0.669811 0.5 
--0.036487 0.171225 0.000545037 0.438578 0.5 
--0.0664352 0.117198 -0.00987161 0.569796 0.5 
--0.0682606 0.170398 -0.0436995 0.381568 0.451091 
--0.090925 0.14605 0.0190382 0.648478 0.5 
-0.00678622 0.115841 0.0388077 0.549283 0.408623 
-0.0310139 0.0930696 -0.017798 0.732658 0.5 
-0.0056976 0.10589 0.0435511 0.592572 0.5 
--0.0706519 0.13063 0.0502497 0.563116 0.5 
-0.0059746 0.130858 0.00579479 0.795238 0.5 
-0.0184217 0.0423182 0.042477 0.259499 0.426724 
-0.0147876 0.0909747 0.0509658 0.654705 0.5 
--0.00598232 0.115409 0.0402027 0.615633 0.5 
--0.0811312 0.117972 -0.00359453 0.505277 0.5 
--0.0787032 0.144274 -0.00389052 0.466714 0.5 
-0.00581988 0.106226 -0.0208968 0.792948 0.5 
--0.0192761 0.119853 0.0328061 0.445477 0.415699 
--0.00593116 0.130215 0.005954 0.738924 0.5 
--0.0893322 0.142745 0.0290326 0.80362 0.5 
--0.00762538 0.123273 -0.00981555 0.767738 0.284429 
--0.0692263 0.178922 -0.0542743 0.245129 0.411885 
--0.0298757 0.124252 0.0209674 0.32811 0.5 
--0.0848266 0.148987 0.0327697 0.331963 0.314683 
--0.0888516 0.0909723 0.0179034 0.603378 0.5 
--0.0305879 0.122384 -0.00635771 0.63839 0.5 
--0.0307198 0.117989 0.0306166 0.543293 0.5 
--0.0780612 0.120653 0.0513999 0.490413 0.5 
-0.0332714 0.108498 -0.00743195 0.534403 0.5 
--0.0677112 0.0928918 -0.0168814 0.511499 0.5 
--0.075666 0.0911817 -0.0136967 0.429902 0.5 
--0.082422 0.0951121 0.0310878 0.678588 0.5 
--0.0856984 0.136903 0.00192122 0.517441 0.5 
--0.0292804 0.0417747 0.051397 0.553401 0.5 
--0.017732 0.0423864 0.051684 0.709553 0.5 
--0.0656987 0.171007 -0.056644 0.549906 0.5 
--0.0298523 0.170905 -0.0165609 0.436075 0.5 
--0.0562502 0.135013 0.0330455 0.727547 0.5 
--0.0666127 0.133021 0.0447044 0.724494 0.5 
--0.0425379 0.155441 -0.00749353 0.424682 0.5 
--0.0545308 0.0714603 0.0397042 0.682177 0.456916 
--0.0413159 0.0906923 -0.0225881 0.72469 0.5 
--0.0172876 0.0921774 0.0536212 0.546444 0.5 
--0.00598119 0.0940308 0.0542643 0.455087 0.5 
-0.0423724 0.0672563 0.0295801 0.33948 0.5 
-0.0285741 0.116909 -0.00391772 0.66246 0.5 
--0.0331811 0.0450744 0.0451146 0.432059 0.466683 
--0.0539402 0.118566 0.0353731 0.515399 0.5 
-0.0422724 0.0795546 -0.00579461 0.568535 0.5 
-0.0297273 0.0425502 0.0304975 0.650152 0.5 
--0.0315639 0.0959331 -0.0236801 0.474586 0.431409 
-0.0381804 0.105121 0.0266947 0.534482 0.490368 
--0.0284988 0.090492 -0.0290854 0.294426 0.332222 
--0.0173189 0.0437942 0.0432695 0.576068 0.5 
-0.00376754 0.0477551 0.0502037 0.495901 0.44823 
-0.0432673 0.0458291 0.0278251 0.807573 0.5 
--0.0233322 0.181239 -0.0112893 0.246322 0.458572 
--0.0056258 0.0565038 0.0538818 0.61481 0.5 
-0.00529431 0.0556798 0.0532881 0.560812 0.423049 
--0.0883219 0.105757 0.0172983 0.604102 0.5 
--0.0566374 0.0470184 0.0305809 0 0 
--0.0296243 0.0543188 0.0398951 0.676102 0.5 
--0.00597407 0.105897 0.0440669 0.338462 0.5 
--0.0214122 0.0546976 0.044641 0.195646 0.404388 
--0.0161488 0.0574363 0.050904 0.451613 0.5 
--0.0568305 0.146392 -0.0026426 0.48145 0.5 
--0.0931466 0.119067 0.0179948 0.570519 0.5 
--0.061862 0.158417 -0.0293026 0.690546 0.5 
--0.0855858 0.10684 0.021729 0.519516 0.5 
-0.0336642 0.0540543 0.0350841 0.609925 0.5 
-0.042771 0.0560351 0.031559 0.669803 0.5 
--0.0434589 0.117191 0.0317044 0.657986 0.5 
--0.0680962 0.156721 -0.0426174 0.523327 0.5 
-0.0272384 0.103156 0.0397058 0.689793 0.5 
--0.0293932 0.178536 -0.0145563 0.314049 0.5 
--0.0762697 0.0912245 0.0383419 0.647987 0.457049 
--0.0191285 0.0985952 0.0456676 0.271215 0.427554 
--0.053091 0.0567402 0.0293963 0.192432 0.5 
--0.0431978 0.0555777 0.0390838 0.311543 0.5 
--0.0833055 0.115643 0.046828 0.438131 0.5 
-0.0144345 0.127081 0.026297 0.479299 0.429147 
--0.0388913 0.123761 0.0249778 0.514489 0.5 
--0.0594359 0.119905 0.0399756 0.634635 0.5 
--0.0702332 0.154262 -0.0312401 0.685413 0.5 
--0.0574473 0.152576 0.0284508 0.93076 0.5 
--0.0480038 0.056366 0.0362663 0.58186 0.5 
--0.0107262 0.179662 -0.0277472 0.400699 0.458536 
--0.0882293 0.106066 0.00846756 0.477822 0.5 
--0.078994 0.153984 0.00651862 0.57436 0.5 
--0.0295675 0.126072 0.0146338 0.393422 0.5 
--0.0817356 0.15439 0.0177332 0.505065 0.5 
--0.0795469 0.104194 -0.00620274 0.528684 0.5 
--0.0248608 0.122913 0.0245429 0.379391 0.5 
--0.0664416 0.159957 -0.0533713 0.38665 0.5 
--0.0784878 0.0705283 0.0174461 0.703257 0.5 
--0.00967101 0.173225 -0.0264945 0.379771 0.5 
--0.0566284 0.0547031 0.00744563 0.270787 0.5 
--0.0184015 0.122219 -0.00775134 0.782181 0.5 
--0.0695952 0.146412 -0.018032 0.130446 0.5 
--0.0412517 0.123196 -0.00958087 0.590842 0.5 
--0.0684972 0.148194 -0.028726 0.690046 0.5 
--0.0540036 0.055543 0.0177674 0.079935 0 
--0.0169203 0.0682168 0.0531499 0.608033 0.445048 
--0.00607221 0.0677102 0.0564501 0.650491 0.470895 
-0.00708728 0.0673218 0.0553369 0.748671 0.5 
--0.0143174 0.116971 0.037836 0.441459 0.5 
-0.0538923 0.0557547 0.0266244 0.405493 0.41666 
-0.00517855 0.0931738 0.0535873 0.395048 0.366076 
--0.0431038 0.0674388 0.0407737 0.587502 0.5 
--0.0293069 0.0680733 0.041016 0.650585 0.5 
--0.0379555 0.161954 -0.0128021 0.499753 0.5 
--0.0561165 0.0654329 0.0341979 0.277414 0.5 
--0.0761707 0.155559 -0.0059272 0.708579 0.5 
--0.0552181 0.122506 -0.00946488 0.538005 0.5 
-0.0177004 0.105983 -0.0186138 0.576137 0.468722 
-0.0534583 0.0656375 0.0264336 0.501229 0.5 
--0.0869152 0.0944156 0.00293118 0.494536 0.346642 
--0.0764257 0.161707 -0.0297517 0.476378 0.5 
--0.0440959 0.127453 -0.00327875 0.853498 0.5 
--0.0312919 0.0798298 0.0434944 0.693464 0.5 
--0.0549448 0.106348 -0.0185625 0.484023 0.5 
--0.0723735 0.110057 -0.00943257 0.44421 0.5 
--0.0553659 0.0919829 -0.0211783 0.619673 0.5 
--0.0488091 0.0660127 0.0373959 0.829801 0.5 
--0.0473086 0.145156 0.00688469 0.636632 0.45621 
--0.0803913 0.129634 -0.00469755 0.386393 0.5 
--0.041802 0.105934 -0.0198692 0.79815 0.5 
--0.00632139 0.0931652 -0.0328935 0.564234 0.5 
--0.00597054 0.106138 -0.0222282 0.740261 0.5 
--0.0294827 0.158293 -0.00619266 0.209483 0.5 
--0.0177953 0.106289 -0.0217771 0.723165 0.5 
--0.0885261 0.137839 0.0393964 0.651389 0.5 
--0.0674935 0.128392 -0.00863471 0.737784 0.5 
-0.0463693 0.0715128 0.0216754 0.461473 0.448797 
--0.0409565 0.117168 -0.0145809 0.602235 0.5 
--0.0106656 0.167541 -0.0199013 0.359593 0.5 
--0.0532547 0.157456 -0.00281896 0.292939 0.5 
-0.00530988 0.0933129 -0.0301852 0.75972 0.5 
--0.0773436 0.0727226 0.0266546 0.757943 0.5 
--0.0625087 0.149934 -0.0150319 0.415531 0.480025 
--0.0688014 0.0685726 0.0306649 0.49936 0.45677 
--0.0545252 0.0808478 -0.0201707 0.75515 0.5 
--0.0436768 0.078916 0.0428855 0.696934 0.5 
--0.0185748 0.0789703 0.0557353 0.607912 0.5 
--0.00599993 0.0794548 0.0578008 0.791265 0.5 
-0.00706485 0.0811917 0.0558187 0.523043 0.5 
--0.0850269 0.146034 0.00585954 0.583528 0.5 
-0.0370111 0.110397 0.00265294 0.516602 0.481774 
--0.0683084 0.0803316 0.0407109 0.610448 0.476331 
--0.055894 0.0792594 0.0435335 0.634349 0.5 
-0.0381456 0.0881056 -0.0138675 0.676152 0.5 
--0.0642837 0.0396418 0.039624 0.532543 0.5 
--0.0698696 0.168536 -0.0313319 0.458525 0.324439 
--0.061796 0.155741 -0.0207923 0.443336 0.5 
--0.0622848 0.16236 -0.0396288 0.427869 0.464762 
--0.0686864 0.0923704 0.0421978 0.59211 0.5 
--0.049353 0.139298 0.0147955 0.761861 0.5 
--0.0784177 0.110126 0.0417886 0.498936 0.5 
-0.0179416 0.0792747 0.0518862 0.491924 0.475524 
-0.00532732 0.123661 -0.00997105 0.555015 0.5 
--0.0556774 0.0935206 0.044207 0.778337 0.5 
--0.0431924 0.0921154 0.0432689 0.605881 0.5 
--0.0298626 0.0940124 0.0444805 0.668172 0.5 
-0.0205955 0.087113 0.0492325 0.678548 0.5 
-0.01721 0.127663 0.00512593 0.595962 0.5 
--0.0290125 0.106719 -0.0207479 0.809584 0.5 
-0.0185443 0.0948112 0.0477587 0.669841 0.5 
--0.00588676 0.116622 -0.0160049 0.826286 0.5 
--0.0528191 0.162649 0.00296711 0.343566 0.5 
-0.0358078 0.0958594 -0.0120328 0.738943 0.5 
--0.0912064 0.131415 0.0295307 0.816274 0.5 
--0.067874 0.106952 0.0403725 0.481571 0.5 
--0.0441636 0.104918 0.0401706 0.648927 0.395789 
-0.00749586 0.09835 0.0488255 0.46146 0.5 
--0.0554961 0.103898 0.0411405 0.529374 0.5 
--0.0669044 0.115717 0.0473479 0.429195 0.5 
--0.0501524 0.140326 0.00258818 0.569746 0.5 
--0.0554508 0.13242 -0.00485445 0.673026 0.5 
--0.014752 0.181897 -0.0262781 0.40888 0.5 
--0.029558 0.161783 -0.0143368 0.852313 0.5 
--0.0561854 0.111277 0.0373713 0.588374 0.5 
--0.040984 0.110496 0.0370883 0.553647 0.5 
--0.0320055 0.110468 0.0370438 0.565129 0.5 
-0.0250033 0.110611 0.0368459 0.631257 0.5 
--0.046987 0.147434 -0.00222536 0.521986 0.5 
--0.0183407 0.0352362 0.0507938 0.291685 0.457265 
--0.0178406 0.170484 -0.0181143 0.809186 0.5 
--0.0569472 0.0349416 0.0423717 0.341981 0.5 
-0.00583339 0.0351076 0.0420914 0.261253 0.345588 
--0.0428024 0.0351574 0.0416872 0.193197 0.5 
--0.066462 0.104777 -0.0148582 0.608847 0.5 
-0.0257452 0.0459137 0.0381185 0.444171 0.5 
-0.0379451 0.0817167 -0.0141547 0.644934 0.5 
--0.0844262 0.0797714 0.0186332 0.67606 0.5 
-0.0532504 0.04759 0.0181903 0.342211 0.398387 
-0.0186424 0.0536035 0.046215 0.589102 0.5 
-0.00732515 0.118243 -0.0153012 0.54369 0.457314 
--0.0314704 0.157066 0.000976216 0.445666 0.44081 
-0.0286229 0.056876 0.0407635 0.635463 0.446542 
-0.0581591 0.0550016 0.0180254 0.474964 0.5 
-0.016864 0.089935 -0.0269104 0.546403 0.5 
-0.0145778 0.0585769 0.0501691 0.387785 0.5 
-0.0367248 0.0918184 0.0366248 0.726421 0.5 
--0.0198801 0.166404 -0.0112699 0.688671 0.5 
-0.0150294 0.0677357 0.0520671 0.554385 0.463079 
-0.0210524 0.0681161 0.0484346 0.414803 0.412252 
-0.0298776 0.0679936 0.0419172 0.611901 0.5 
-0.0368358 0.0678495 0.036641 0.593561 0.5 
-0.0574748 0.0682218 0.0171425 0.550839 0.448044 
-0.0316842 0.0785087 -0.019208 0.760295 0.5 
--0.0760271 0.175704 -0.0506937 0.340571 0.5 
--0.0655396 0.0607885 0.0175707 0.414933 0.425841 
--0.0806026 0.081447 0.0306516 0.756683 0.5 
-0.0189749 0.121506 -0.00694565 0.549 0.5 
-0.030684 0.0795461 0.0431507 0.572664 0.5 
-0.0371888 0.0792484 0.0367937 0.505468 0.5 
-0.0419366 0.0795911 0.0295911 0.645662 0.5 
-0.046032 0.0793694 0.0177694 0.458504 0.467907 
--0.0787921 0.0707773 0.00685585 0.704234 0.277826 
--0.0293987 0.115917 -0.0147065 0.856895 0.5 
--0.0869924 0.113518 0.00410409 0.344807 0.5 
--0.0142186 0.174013 -0.0259807 0.439072 0.5 
-0.0174795 0.0352131 -0.00592856 0 0 
-0.0162141 0.0358475 -0.0162131 0.173751 0.5 
-0.0193248 0.0358322 0.0313206 0.156956 0.287305 
-0.0435544 0.0411101 0.00579916 0.245023 0.5 
-0.0226191 0.0406052 -0.00793544 0.173629 0.5 
-0.0191348 0.042782 -0.0192095 0.367832 0.5 
-0.0414633 0.0456301 -0.00354513 0.514406 0.5 
-0.0436925 0.0411968 0.01772 0.265572 0.5 
-0.0512872 0.0463959 0.00580531 0.199267 0.5 
-0.0285777 0.105181 -0.0142381 0.728425 0.5 
-0.0306748 0.0445124 -0.00617993 0.464947 0.5 
--0.0184118 0.0948059 -0.0307434 0.520871 0.5 
--0.0315484 0.0343023 -0.0284081 0.16856 0.5 
-0.0260381 0.0475902 -0.0165794 0.515417 0.5 
-0.0554197 0.0686378 0.00589653 0.629664 0.372945 
-0.0520374 0.055073 -0.0024816 0.592036 0.5 
-0.0567375 0.0542224 0.00512483 0.511629 0.5 
-0.0428049 0.0553286 -0.00604704 0.434179 0.5 
--0.0620037 0.167422 -0.0527165 0.538383 0.466596 
-0.0341128 0.0541776 -0.00948346 0.591066 0.5 
-0.029518 0.0560564 -0.0175875 0.574224 0.5 
--0.0177887 0.115911 -0.0157838 0.559736 0.5 
--0.0417838 0.0357602 -0.0264107 0.0979878 0.5 
--0.00518939 0.043046 -0.0273333 0.274297 0.5 
--0.0664059 0.0343649 -0.00416668 0.135623 0.5 
-0.0475414 0.0712174 0.00542617 0.590477 0.5 
-0.0249138 0.0825163 -0.0245877 0.759593 0.5 
--0.0299024 0.0426031 -0.0283179 0.537642 0.5 
-0.0218121 0.0515865 -0.0236492 0.56032 0.5 
--0.0271537 0.0351608 0.0509267 0.96808 0.5 
-0.0161181 0.11563 -0.0145451 0.45799 0.403894 
-0.031738 0.0679983 -0.0183532 0.581486 0.5 
-0.0418226 0.0675201 -0.00551555 0.572144 0.5 
-0.0514871 0.0637279 -0.00174794 0.518067 0.5 
--0.0893303 0.128309 0.0428023 0.633972 0.457764 
-0.0459385 0.0796307 0.00579632 0.323813 0.5 
--0.0705433 0.149897 -0.0387319 0.143598 0.5 
--0.0429617 0.0430242 -0.0176288 0.371561 0.5 
--0.0719677 0.177848 -0.0474604 0.498199 0.393806 
--0.0760529 0.177651 -0.0471457 0.200482 0.341482 
-0.0304173 0.118495 0.00573814 0.517745 0.5 
--0.0771451 0.167706 -0.0298798 0.259817 0.452429 
-0.0202668 0.092861 -0.0237363 0.630702 0.48336 
--0.0254815 0.0798697 0.0510546 0.764034 0.5 
--0.0650541 0.0353259 0.0162237 0.352362 0.5 
--0.0647676 0.0350792 0.0294481 0.161121 0.384305 
--0.0644267 0.0414591 0.0304476 0.206373 0.5 
--0.06432 0.0352261 0.0387914 0.349097 0.5 
--0.0676 0.0340299 0.00590491 0.228898 0.5 
--0.0679534 0.0418588 0.00668394 0.30841 0.5 
--0.0573497 0.0431548 0.0200229 0 0 
--0.0634632 0.0414321 0.0142052 0.258252 0.450399 
--0.059413 0.0471382 0.00628538 0.460736 0.319245 
--0.0233834 0.0656416 0.0450976 0.709715 0.5 
--0.063538 0.071665 0.0379463 0.556494 0.5 
--0.0193036 0.0810128 -0.0384318 0.500126 0.449734 
--0.0427206 0.0343557 -0.0191302 0.176398 0.205782 
--0.00690237 0.03464 -0.0202171 0.15305 0.5 
--0.0656787 0.0408332 -0.00401793 0.169982 0.409113 
--0.0383907 0.0419218 -0.0264039 0.3765 0.5 
--0.0556585 0.0432866 -0.00758834 0.62257 0.5 
--0.0416785 0.0420276 -0.00999679 0.340556 0.5 
--0.0322294 0.0446593 -0.0167499 0.299501 0.5 
--0.0307385 0.0563307 -0.018517 0.265727 0.5 
--0.0429026 0.0561897 -0.0113043 0.555432 0.5 
--0.0550285 0.0566557 -0.00531375 0.527245 0.5 
--0.0261858 0.0568836 -0.0282694 0.366688 0.5 
--0.0552189 0.117461 -0.0133744 0.568329 0.5 
--0.0190658 0.0546695 -0.0318646 0.484351 0.5 
--0.0687629 0.0686694 -0.00654941 0.168435 0.5 
--0.0730504 0.06542 0.00552859 0.275779 0.5 
--0.0207234 0.0672793 -0.036553 0.45692 0.5 
--0.0290792 0.067426 -0.0290521 0.452259 0.5 
--0.0328056 0.0664637 -0.0195215 0.908229 0.5 
--0.0177608 0.0343319 -0.0259142 0.174612 0.215481 
--0.0773687 0.0732571 -0.00409771 0.293636 0.296358 
-0.0151616 0.126104 -0.00266395 0.542796 0.5 
--0.0845255 0.0800572 0.00530702 0.615888 0.5 
--0.0793517 0.0798559 -0.00640565 0.260107 0.5 
--0.0309728 0.0794701 -0.0312475 0.64535 0.304239 
--0.0355144 0.081801 -0.0226887 0.930953 0.5 
--0.068141 0.0801227 -0.0164278 0.485274 0.5 
--0.0512932 0.034227 -0.0129013 0.159841 0.5 
-0.0161924 0.080479 -0.0292174 0.750174 0.5 
--0.0144478 0.0879274 -0.0380297 0.689122 0.5 
--0.0173157 0.0432674 -0.0282906 0.230538 0.5 
--0.0193328 0.0979251 -0.024792 0.661276 0.5 
--0.0555479 0.0336816 -0.00619013 0.1361 0.5 
-0.00702627 0.0978418 -0.0246055 0.732067 0.326346 
--0.0148892 0.126068 -0.00252126 0.467449 0.5 
-0.0175205 0.0552114 -0.0272756 0.685576 0.5 
--0.00953661 0.0794104 -0.0379859 0.670336 0.467319 
-0.00524266 0.0391336 -0.021947 0.540697 0.5 
-0.0175653 0.0679339 -0.0289388 0.690366 0.5 
--0.0057907 0.128077 -0.00285105 0.714685 0.5 
-0.00626556 0.128047 -0.0031705 0.574275 0.5 
-0.00559979 0.0346604 -0.0179318 0.278473 0.5 
-0.029824 0.0359142 0.00488977 0.290019 0.5 
-0.00625193 0.0459623 -0.0263782 0.665265 0.460024 
-0.0143253 0.0473484 -0.0251513 0.546545 0.456757 
-0.00604086 0.0555073 -0.0304314 0.840924 0.5 
--0.00613413 0.0546372 -0.032635 0.634884 0.475184 
--0.0346694 0.057124 -0.0114953 0.102172 0.5 
--0.00684543 0.0679742 -0.0359406 0.670518 0.457134 
-0.0056558 0.0676237 -0.0329199 0.79033 0.385997 
--0.0569732 0.0651628 -0.00958219 0.452904 0.5 
--0.0422796 0.0699944 -0.0161463 0.543504 0.5 
--0.0175719 0.0705473 -0.0382261 0.581028 0.470136 
--0.055586 0.0722983 -0.0161218 0.401473 0.5 
--0.0637884 0.0712697 -0.0138535 0.437166 0.5 
-0.00568561 0.0790547 -0.0339189 0.719764 0.5 
--0.00338429 0.0804511 -0.0367226 0.799862 0.5 
--0.0248988 0.0815004 -0.0371078 0.39297 0.457854 
--0.0412513 0.0791378 -0.0197746 0.273711 0.5 
--0.0735819 0.0777026 -0.0122023 0.445372 0.5 
--0.018062 0.0352627 -0.0195401 0.319674 0.5 
--0.031577 0.0358487 -0.0179669 0.482378 0.5 
--0.00602034 0.0381237 -0.0145184 0.909294 0.5 
--0.0177811 0.0382546 -0.0154503 0.887215 0.5 
-0.00753447 0.0355596 -0.00650063 0.962688 0.5 
-0.00430437 0.0384017 -0.0071754 0.927286 0.5 
--0.00593935 0.038948 -0.00592129 0.816802 0.5 
--0.0176142 0.0386055 -0.00584508 0.759701 0.5 
--0.0430308 0.0341391 -0.00565972 0.772585 0.5 
-0.0189222 0.0351076 0.00499769 0.579133 0.5 
--0.0299129 0.0383912 -0.00582677 0.752109 0.5 
-0.00512066 0.0348398 0.00558498 0.588251 0.5 
-0.00103528 0.0375917 0.000952222 0.441385 0.5 
--0.00584714 0.0383419 0.00590803 0.728422 0.5 
--0.0424621 0.0343144 0.00590597 0.266658 0.5 
--0.017873 0.0383166 0.00599471 0.753895 0.5 
-0.028662 0.0358411 0.0187496 0.360666 0.5 
--0.055026 0.0336204 0.00583816 0.742717 0.5 
--0.0284733 0.0381489 0.00441853 0.456211 0.5 
--0.000947006 0.0357374 0.0103469 0.779853 0.5 
-0.0193224 0.0351814 0.0196616 0.180494 0.5 
--0.0342325 0.033759 0.00717517 0.152905 0 
-0.00536022 0.0345956 0.0179871 0.676527 0.5 
--0.000385714 0.0351459 0.0134171 0.848157 0.5 
-0.0334119 0.0376179 0.0210082 0.70177 0.5 
--0.00589791 0.0381782 0.0177062 0.797449 0.5 
--0.0352445 0.0350571 0.0178257 0.572312 0.5 
--0.0178078 0.0381962 0.0178114 0.753708 0.5 
--0.0261898 0.0377592 0.0177044 0.146481 0.5 
--0.0563247 0.0336762 0.0175265 0.458851 0.5 
-0.00114114 0.037661 0.0223414 0.978558 0.5 
-0.0100253 0.0355029 0.029656 0.701449 0.5 
-0.00550127 0.0385556 0.0296609 0.996029 0.5 
--0.00596581 0.0388946 0.0299252 0.805634 0.5 
--0.0330745 0.0355217 0.0292236 0.263742 0.5 
--0.0277717 0.0382563 0.0322865 0.074682 0.5 
--0.0179091 0.0385902 0.0296167 0.782021 0.5 
--0.0419404 0.0343698 0.0299668 0.109729 0 
-0.015243 0.0356116 0.0412692 0.759188 0.5 
--0.0554301 0.0342555 0.0297952 0.808252 0.5 
--0.0660515 0.0611144 0.00585548 0.442355 0.5 
--0.00654912 0.0350372 0.0453959 0.139343 0 
--0.0307826 0.0347596 0.0432959 0.154826 0.5 
--0.0180834 0.0348142 0.0458772 0.143796 0.5 
-3 164 94 98 
-3 224 335 49 
-3 331 350 376 
-3 124 122 237 
-3 61 89 69 
-3 61 161 94 
-3 24 89 50 
-3 109 25 35 
-3 27 34 152 
-3 444 443 435 
-3 94 35 153 
-3 3 61 69 
-3 24 69 89 
-3 38 218 104 
-3 22 42 39 
-3 14 24 34 
-3 290 166 371 
-3 226 76 224 
-3 204 197 72 
-3 82 3 14 
-3 13 81 23 
-3 99 13 23 
-3 23 110 30 
-3 110 2 30 
-3 166 265 371 
-3 90 61 3 
-3 34 24 50 
-3 293 167 207 
-3 80 78 85 
-3 61 94 164 
-3 84 238 80 
-3 4 161 61 
-3 132 149 64 
-3 196 22 228 
-3 59 46 242 
-3 179 84 80 
-3 265 96 371 
-3 52 258 207 
-3 121 127 141 
-3 343 168 346 
-3 232 227 220 
-3 232 243 227 
-3 232 246 243 
-3 57 126 56 
-3 57 130 126 
-3 221 232 220 
-3 4 61 90 
-3 134 80 85 
-3 176 217 175 
-3 4 0 161 
-3 78 21 50 
-3 126 130 129 
-3 56 126 129 
-3 111 182 201 
-3 96 70 371 
-3 89 164 98 
-3 123 6 55 
-3 197 87 72 
-3 416 419 412 
-3 245 80 179 
-3 21 78 36 
-3 61 164 89 
-3 67 132 64 
-3 150 149 132 
-3 384 387 325 
-3 214 221 112 
-3 214 233 232 
-3 221 214 232 
-3 244 246 232 
-3 233 244 232 
-3 244 252 246 
-3 244 143 119 
-3 252 244 119 
-3 127 142 141 
-3 67 150 132 
-3 82 90 3 
-3 112 180 214 
-3 244 253 143 
-3 111 201 269 
-3 37 74 63 
-3 133 150 67 
-3 118 133 67 
-3 133 180 150 
-3 191 214 180 
-3 181 191 180 
-3 191 234 233 
-3 214 191 233 
-3 234 244 233 
-3 234 7 244 
-3 244 98 253 
-3 253 98 143 
-3 216 217 115 
-3 181 180 133 
-3 15 16 219 
-3 254 98 244 
-3 7 254 244 
-3 74 11 63 
-3 14 3 24 
-3 3 69 24 
-3 217 216 175 
-3 85 78 50 
-3 73 78 80 
-3 7 98 254 
-3 105 133 118 
-3 1 248 196 
-3 48 241 100 
-3 42 156 39 
-3 149 173 344 
-3 135 133 105 
-3 106 135 105 
-3 31 7 234 
-3 148 31 234 
-3 89 98 7 
-3 31 89 7 
-3 235 84 230 
-3 14 27 236 
-3 106 125 135 
-3 19 20 62 
-3 131 54 159 
-3 34 50 21 
-3 82 14 236 
-3 201 52 43 
-3 310 308 280 
-3 131 159 54 
-3 271 310 280 
-3 27 14 34 
-3 177 89 31 
-3 238 73 80 
-3 130 176 175 
-3 354 331 381 
-3 129 130 175 
-3 125 136 135 
-3 251 52 201 
-3 106 56 125 
-3 56 129 136 
-3 125 56 136 
-3 129 175 174 
-3 136 129 174 
-3 175 216 215 
-3 174 175 215 
-3 115 114 215 
-3 216 115 215 
-3 134 85 31 
-3 85 177 31 
-3 50 89 177 
-3 85 50 177 
-3 179 80 245 
-3 400 407 367 
-3 263 83 121 
-3 217 179 115 
-3 149 132 64 
-3 178 187 116 
-3 142 178 116 
-3 326 120 319 
-3 57 83 267 
-3 304 391 294 
-3 355 354 359 
-3 128 29 11 
-3 267 273 130 
-3 48 16 10 
-3 301 302 266 
-3 196 66 22 
-3 230 84 217 
-3 247 13 243 
-3 110 81 13 
-3 271 178 266 
-3 110 13 247 
-3 278 277 267 
-3 48 10 329 
-3 258 11 275 
-3 1 196 228 
-3 154 247 243 
-3 154 110 247 
-3 263 141 270 
-3 154 60 110 
-3 60 154 110 
-3 154 60 110 
-3 11 74 37 
-3 274 5 51 
-3 252 154 243 
-3 119 252 243 
-3 109 110 60 
-3 39 2 110 
-3 109 39 110 
-3 32 128 29 
-3 32 128 11 
-3 309 300 311 
-3 252 119 154 
-3 73 145 255 
-3 67 64 259 
-3 32 29 128 
-3 258 275 43 
-3 154 119 60 
-3 119 109 60 
-3 137 256 248 
-3 270 267 83 
-3 235 238 84 
-3 267 130 57 
-3 258 32 11 
-3 302 310 271 
-3 51 238 235 
-3 266 302 271 
-3 5 36 255 
-3 51 235 230 
-3 51 145 73 
-3 286 51 230 
-3 287 274 286 
-3 119 25 109 
-3 10 40 289 
-3 120 48 329 
-3 274 51 286 
-3 276 230 217 
-3 10 16 15 
-3 51 5 145 
-3 43 11 201 
-3 176 276 217 
-3 143 25 119 
-3 158 207 167 
-3 360 321 357 
-3 130 273 276 
-3 122 198 237 
-3 270 278 267 
-3 77 218 38 
-3 15 6 40 
-3 280 187 178 
-3 271 280 178 
-3 258 207 32 
-3 66 58 22 
-3 279 287 278 
-3 155 139 172 
-3 121 141 263 
-3 288 41 274 
-3 287 288 274 
-3 276 176 130 
-3 289 288 205 
-3 274 41 5 
-3 288 287 279 
-3 329 10 289 
-3 16 100 219 
-3 127 178 142 
-3 273 267 276 
-3 252 119 243 
-3 116 279 141 
-3 41 123 5 
-3 116 288 279 
-3 142 116 141 
-3 207 158 32 
-3 276 277 230 
-3 101 102 163 
-3 299 298 294 
-3 287 286 278 
-3 5 255 145 
-3 131 159 70 
-3 275 11 43 
-3 32 158 250 
-3 205 288 116 
-3 73 36 78 
-3 120 329 319 
-3 297 391 300 
-3 84 179 217 
-3 17 77 38 
-3 255 36 73 
-3 263 270 83 
-3 249 248 1 
-3 286 230 277 
-3 11 37 66 
-3 43 52 258 
-3 267 277 276 
-3 279 278 270 
-3 141 279 270 
-3 51 73 238 
-3 47 36 5 
-3 201 66 269 
-3 201 11 66 
-3 309 310 302 
-3 300 309 302 
-3 182 33 251 
-3 278 286 277 
-3 243 246 252 
-3 416 427 419 
-3 96 131 70 
-3 66 256 111 
-3 65 335 189 
-3 113 374 407 
-3 144 139 155 
-3 226 224 139 
-3 358 400 396 
-3 30 91 203 
-3 226 139 144 
-3 46 328 242 
-3 307 304 298 
-3 70 159 54 
-3 103 265 284 
-3 443 261 446 
-3 17 38 28 
-3 88 200 239 
-3 72 170 211 
-3 138 17 28 
-3 35 1 228 
-3 295 299 294 
-3 18 131 140 
-3 18 59 131 
-3 207 258 52 
-3 188 70 54 
-3 104 87 197 
-3 222 48 120 
-3 325 326 311 
-3 326 281 120 
-3 54 159 292 
-3 386 299 295 
-3 138 59 17 
-3 48 100 16 
-3 59 242 17 
-3 296 121 83 
-3 10 15 40 
-3 242 91 17 
-3 225 9 211 
-3 314 322 384 
-3 326 325 281 
-3 170 225 211 
-3 17 91 77 
-3 144 76 226 
-3 155 9 225 
-3 159 131 28 
-3 172 139 170 
-3 131 138 28 
-3 281 264 120 
-3 264 222 120 
-3 139 155 225 
-3 139 225 170 
-3 314 325 313 
-3 386 295 390 
-3 292 159 28 
-3 132 149 344 
-3 424 427 416 
-3 49 335 65 
-3 314 313 304 
-3 111 269 66 
-3 9 71 72 
-3 211 9 72 
-3 306 316 353 
-3 307 314 304 
-3 325 311 313 
-3 40 41 288 
-3 289 40 288 
-3 40 6 41 
-3 6 123 41 
-3 22 39 109 
-3 165 312 76 
-3 299 307 298 
-3 144 165 76 
-3 312 107 76 
-3 376 381 331 
-3 165 107 312 
-3 155 172 330 
-3 35 228 22 
-3 45 184 160 
-3 42 62 156 
-3 2 39 62 
-3 58 42 22 
-3 49 71 9 
-3 280 116 187 
-3 280 205 116 
-3 155 330 144 
-3 280 289 205 
-3 319 280 308 
-3 162 77 20 
-3 20 77 91 
-3 329 289 280 
-3 319 329 280 
-3 156 62 39 
-3 372 408 375 
-3 190 1 0 
-3 1 35 0 
-3 42 19 62 
-3 35 161 0 
-3 190 0 97 
-3 35 22 109 
-3 76 53 224 
-3 161 35 94 
-3 49 9 155 
-3 224 49 155 
-3 29 63 11 
-3 160 162 19 
-3 76 333 53 
-3 153 25 143 
-3 71 49 65 
-3 2 20 30 
-3 62 20 2 
-3 55 8 5 
-3 169 0 4 
-3 6 8 55 
-3 35 25 153 
-3 160 218 162 
-3 218 77 162 
-3 15 334 6 
-3 334 8 6 
-3 332 76 93 
-3 8 47 5 
-3 98 153 143 
-3 94 153 98 
-3 219 334 15 
-3 332 333 76 
-3 93 76 107 
-3 100 334 219 
-3 160 19 45 
-3 19 162 20 
-3 340 132 344 
-3 45 19 42 
-3 27 47 8 
-3 27 36 47 
-3 80 115 179 
-3 45 42 58 
-3 71 184 45 
-3 236 27 8 
-3 334 236 8 
-3 332 93 333 
-3 27 152 36 
-3 223 64 340 
-3 236 334 117 
-3 152 21 36 
-3 134 148 115 
-3 115 148 114 
-3 152 34 21 
-3 5 123 55 
-3 337 68 191 
-3 333 93 282 
-3 256 66 196 
-3 135 174 347 
-3 183 180 195 
-3 117 285 236 
-3 182 111 63 
-3 354 318 352 
-3 114 234 68 
-3 71 65 184 
-3 135 136 174 
-3 191 215 337 
-3 337 215 114 
-3 63 33 182 
-3 133 135 181 
-3 135 347 181 
-3 110 23 81 
-3 157 180 183 
-3 149 157 183 
-3 227 147 220 
-3 12 23 30 
-3 151 99 46 
-3 174 215 191 
-3 99 328 46 
-3 114 148 234 
-3 149 150 157 
-3 220 147 284 
-3 79 186 336 
-3 68 234 191 
-3 396 357 356 
-3 99 23 12 
-3 328 99 12 
-3 337 114 68 
-3 356 358 396 
-3 338 343 342 
-3 223 340 339 
-3 265 103 96 
-3 341 223 339 
-3 347 174 191 
-3 182 251 201 
-3 134 115 80 
-3 12 30 203 
-3 345 343 338 
-3 147 227 103 
-3 33 108 251 
-3 95 20 91 
-3 181 347 191 
-3 345 346 343 
-3 157 150 180 
-3 103 227 18 
-3 66 240 58 
-3 345 344 346 
-3 146 32 108 
-3 445 125 444 
-3 30 95 91 
-3 124 373 374 
-3 137 249 72 
-3 344 345 338 
-3 344 168 346 
-3 12 203 328 
-3 284 147 103 
-3 240 66 37 
-3 344 173 168 
-3 314 384 322 
-3 107 282 93 
-3 76 53 107 
-3 107 53 282 
-3 282 53 333 
-3 165 76 107 
-3 315 202 291 
-3 165 144 76 
-3 407 374 367 
-3 144 53 76 
-3 388 389 92 
-3 155 144 330 
-3 144 224 53 
-3 432 431 434 
-3 155 189 144 
-3 144 189 224 
-3 189 335 53 
-3 224 189 53 
-3 146 29 32 
-3 382 88 209 
-3 331 316 350 
-3 331 353 316 
-3 357 367 366 
-3 360 357 366 
-3 367 374 373 
-3 366 367 373 
-3 373 407 374 
-3 388 92 169 
-3 170 65 155 
-3 155 65 189 
-3 328 203 91 
-3 413 421 414 
-3 356 331 358 
-3 242 328 91 
-3 168 343 346 
-3 113 198 122 
-3 124 113 122 
-3 239 200 315 
-3 331 356 357 
-3 372 26 102 
-3 375 372 102 
-3 26 163 102 
-3 408 372 375 
-3 72 87 65 
-3 170 72 65 
-3 87 184 65 
-3 63 108 11 
-3 63 29 108 
-3 370 285 231 
-3 389 370 231 
-3 131 18 140 
-3 33 63 108 
-3 368 306 321 
-3 374 113 124 
-3 285 324 268 
-3 231 285 268 
-3 336 272 186 
-3 224 155 139 
-3 363 369 372 
-3 86 193 163 
-3 208 63 111 
-3 380 305 202 
-3 356 357 321 
-3 346 354 352 
-3 346 168 354 
-3 168 359 354 
-3 364 290 369 
-3 363 364 369 
-3 290 371 372 
-3 369 290 372 
-3 371 70 26 
-3 372 371 26 
-3 70 188 26 
-3 188 54 26 
-3 54 163 26 
-3 54 86 163 
-3 54 28 86 
-3 28 38 86 
-3 38 197 86 
-3 38 104 197 
-3 104 218 87 
-3 218 160 87 
-3 160 184 87 
-3 58 240 208 
-3 240 37 63 
-3 208 240 63 
-3 340 64 132 
-3 343 168 346 
-3 400 367 357 
-3 396 400 357 
-3 54 292 28 
-3 96 103 18 
-3 346 168 343 
-3 249 137 248 
-3 200 209 199 
-3 79 222 281 
-3 327 308 309 
-3 343 346 352 
-3 383 388 169 
-3 200 88 209 
-3 285 186 324 
-3 241 48 79 
-3 16 100 79 
-3 303 100 79 
-3 323 105 451 
-3 100 303 186 
-3 100 16 79 
-3 321 353 331 
-3 236 285 370 
-3 389 231 92 
-3 100 285 117 
-3 108 63 11 
-3 186 303 79 
-3 88 382 209 
-3 82 236 389 
-3 100 241 79 
-3 45 72 71 
-3 0 169 97 
-3 45 137 72 
-3 285 100 186 
-3 137 45 58 
-3 199 378 305 
-3 208 137 58 
-3 356 331 357 
-3 305 380 202 
-3 378 349 305 
-3 169 92 315 
-3 192 262 75 
-3 361 192 75 
-3 291 202 237 
-3 258 293 207 
-3 272 79 377 
-3 324 186 268 
-3 268 186 88 
-3 90 389 388 
-3 169 315 291 
-3 97 169 291 
-3 79 320 377 
-3 4 383 169 
-3 379 317 368 
-3 200 202 315 
-3 92 239 315 
-3 306 353 321 
-3 370 389 236 
-3 48 222 79 
-3 206 361 185 
-3 361 206 185 
-3 92 231 239 
-3 356 321 331 
-3 190 171 185 
-3 249 190 185 
-3 206 198 361 
-3 198 192 361 
-3 90 388 383 
-3 305 124 237 
-3 327 311 326 
-3 4 90 383 
-3 190 249 1 
-3 206 361 185 
-3 171 206 185 
-3 202 305 237 
-3 108 29 146 
-3 308 310 309 
-3 334 100 117 
-3 90 82 389 
-3 79 336 186 
-3 224 53 335 
-3 354 381 318 
-3 231 268 239 
-3 186 272 209 
-3 88 186 209 
-3 200 199 202 
-3 327 326 319 
-3 308 327 319 
-3 309 311 327 
-3 435 443 446 
-3 199 305 202 
-3 97 171 190 
-3 171 97 206 
-3 97 291 206 
-3 237 198 206 
-3 291 237 206 
-3 406 124 305 
-3 399 402 400 
-3 373 374 407 
-3 300 304 311 
-3 304 313 311 
-3 407 213 113 
-3 208 111 256 
-3 403 402 399 
-3 363 403 399 
-3 29 128 32 
-3 403 375 402 
-3 363 399 359 
-3 194 192 198 
-3 193 86 75 
-3 400 213 407 
-3 272 336 79 
-3 79 281 320 
-3 300 302 297 
-3 294 298 304 
-3 299 322 314 
-3 307 299 314 
-3 322 384 314 
-3 377 281 325 
-3 387 377 325 
-3 281 377 320 
-3 355 358 331 
-3 101 102 262 
-3 363 375 403 
-3 197 204 75 
-3 102 101 262 
-3 299 384 322 
-3 262 163 193 
-3 318 343 352 
-3 299 322 384 
-3 299 393 322 
-3 322 393 384 
-3 137 208 256 
-3 86 197 75 
-3 186 79 336 
-3 222 264 281 
-3 185 361 75 
-3 365 360 366 
-3 386 392 393 
-3 299 386 393 
-3 393 392 384 
-3 392 394 384 
-3 394 398 387 
-3 384 394 387 
-3 404 377 387 
-3 398 404 387 
-3 404 209 377 
-3 209 272 377 
-3 399 400 358 
-3 359 399 358 
-3 101 163 262 
-3 262 193 75 
-3 102 101 375 
-3 204 72 249 
-3 31 148 134 
-3 424 437 427 
-3 359 358 355 
-3 400 402 213 
-3 204 249 185 
-3 351 317 386 
-3 390 351 386 
-3 317 392 386 
-3 392 317 394 
-3 317 395 394 
-3 395 397 398 
-3 394 395 398 
-3 397 405 404 
-3 398 397 404 
-3 199 209 404 
-3 405 199 404 
-3 268 88 239 
-3 75 204 185 
-3 318 352 354 
-3 243 18 227 
-3 397 385 405 
-3 385 199 405 
-3 262 192 194 
-3 101 262 194 
-3 18 131 96 
-3 349 378 199 
-3 385 349 199 
-3 250 158 167 
-3 293 250 167 
-3 379 362 395 
-3 317 379 395 
-3 395 362 397 
-3 362 365 397 
-3 365 401 397 
-3 401 349 385 
-3 397 401 385 
-3 375 194 213 
-3 213 194 113 
-3 375 101 194 
-3 354 352 318 
-3 342 343 318 
-3 375 213 402 
-3 451 261 443 
-3 32 250 293 
-3 258 32 293 
-3 113 194 198 
-3 351 409 368 
-3 355 331 354 
-3 339 340 344 
-3 372 375 363 
-3 339 344 338 
-3 368 321 379 
-3 360 362 379 
-3 360 365 362 
-3 366 365 362 
-3 365 366 362 
-3 406 349 401 
-3 365 406 401 
-3 108 258 52 
-3 258 108 32 
-3 305 349 406 
-3 297 302 301 
-3 52 251 108 
-3 321 360 379 
-3 384 325 314 
-3 373 406 365 
-3 366 373 365 
-3 373 349 406 
-3 349 373 406 
-3 373 124 406 
-3 106 105 323 
-3 439 434 431 
-3 18 243 229 
-3 83 57 260 
-3 447 83 260 
-3 418 425 429 
-3 439 441 434 
-3 441 442 434 
-3 257 106 323 
-3 391 425 418 
-3 435 437 444 
-3 257 323 452 
-3 391 418 294 
-3 296 440 441 
-3 440 296 441 
-3 131 59 138 
-3 294 413 295 
-3 95 30 20 
-3 428 432 434 
-3 422 424 415 
-3 294 420 413 
-3 425 296 429 
-3 414 422 415 
-3 425 121 296 
-3 296 440 431 
-3 452 323 451 
-3 296 83 447 
-3 431 441 439 
-3 445 444 436 
-3 429 296 431 
-3 450 56 106 
-3 301 121 433 
-3 106 257 452 
-3 414 415 411 
-3 390 413 386 
-3 18 229 59 
-3 59 229 46 
-3 386 414 411 
-3 301 433 425 
-3 248 256 196 
-3 411 416 412 
-3 300 391 304 
-3 422 436 424 
-3 46 229 151 
-3 127 121 301 
-3 412 419 356 
-3 295 413 390 
-3 351 390 411 
-3 442 56 125 
-3 409 351 412 
-3 247 243 13 
-3 330 172 155 
-3 451 118 67 
-3 364 44 290 
-3 290 44 166 
-3 166 210 265 
-3 265 210 284 
-3 442 436 434 
-3 229 99 151 
-3 364 449 44 
-3 449 283 44 
-3 418 420 294 
-3 363 449 364 
-3 212 284 210 
-3 44 210 166 
-3 420 428 422 
-3 44 212 210 
-3 247 229 243 
-3 229 247 99 
-3 127 266 178 
-3 56 450 260 
-3 413 420 421 
-3 359 168 363 
-3 363 168 449 
-3 415 424 416 
-3 296 447 260 
-3 212 220 284 
-3 436 437 424 
-3 351 411 412 
-3 440 441 431 
-3 283 212 44 
-3 451 67 261 
-3 168 173 449 
-3 449 173 283 
-3 426 342 318 
-3 381 426 318 
-3 212 348 220 
-3 266 127 301 
-3 426 338 342 
-3 149 283 173 
-3 149 212 283 
-3 438 338 426 
-3 433 121 425 
-3 149 183 212 
-3 414 421 422 
-3 172 170 155 
-3 368 317 351 
-3 350 381 376 
-3 67 259 261 
-3 183 112 212 
-3 212 112 348 
-3 348 112 220 
-3 432 431 434 
-3 448 339 338 
-3 438 448 338 
-3 420 431 432 
-3 112 221 220 
-3 428 420 432 
-3 431 432 434 
-3 417 381 350 
-3 422 428 434 
-3 423 426 381 
-3 417 423 381 
-3 56 260 57 
-3 451 105 118 
-3 296 260 440 
-3 386 413 414 
-3 306 350 316 
-3 448 341 339 
-3 415 416 411 
-3 436 444 437 
-3 259 341 448 
-3 297 425 391 
-3 442 125 445 
-3 450 106 452 
-3 410 350 306 
-3 341 259 223 
-3 355 417 350 
-3 410 355 350 
-3 259 64 223 
-3 410 356 350 
-3 356 410 350 
-3 356 355 410 
-3 355 419 417 
-3 247 13 99 
-3 195 112 183 
-3 180 112 195 
-3 419 355 356 
-3 301 425 297 
-3 390 386 411 
-3 446 259 448 
-3 446 261 259 
-3 434 436 422 
-3 421 420 422 
-3 409 410 306 
-3 368 409 306 
-3 412 356 410 
-3 409 412 410 
-3 442 445 436 
-3 435 423 430 
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/resource/pcd_demo b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/resource/pcd_demo
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/resource/teapot.ply b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/resource/teapot.ply
deleted file mode 100644
index 4c1a671c36c1926561dba64ee0918d31309f0de3..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/resource/teapot.ply
+++ /dev/null
@@ -1,3442 +0,0 @@
-ply
-format ascii 1.0
-element vertex 1177
-property float32 x
-property float32 y
-property float32 z
-element face 2256
-property list uint8 int32 vertex_indices
-end_header
-1.38137 0 2.45469 
-1.4 0 2.4 
-1.35074 -0.375926 2.4 
-1.33276 -0.370922 2.45469 
-1.38426 0 2.4875 
-1.33555 -0.371699 2.4875 
-1.40312 0 2.49844 
-1.35376 -0.376765 2.49844 
-1.43241 0 2.4875 
-1.38201 -0.384628 2.4875 
-1.46655 0 2.45469 
-1.41495 -0.393796 2.45469 
-1.5 0 2.4 
-1.44722 -0.402778 2.4 
-1.21126 -0.711407 2.4 
-1.19514 -0.701938 2.45469 
-1.19764 -0.703409 2.4875 
-1.21396 -0.712995 2.49844 
-1.2393 -0.727875 2.4875 
-1.26884 -0.745225 2.45469 
-1.29778 -0.762222 2.4 
-0.994 -0.994 2.4 
-0.98077 -0.98077 2.45469 
-0.982824 -0.982824 2.4875 
-0.996219 -0.996219 2.49844 
-1.01701 -1.01701 2.4875 
-1.04125 -1.04125 2.45469 
-1.065 -1.065 2.4 
-0.711407 -1.21126 2.4 
-0.701938 -1.19514 2.45469 
-0.703409 -1.19764 2.4875 
-0.712995 -1.21396 2.49844 
-0.727875 -1.2393 2.4875 
-0.745225 -1.26884 2.45469 
-0.762222 -1.29778 2.4 
-0.375926 -1.35074 2.4 
-0.370922 -1.33276 2.45469 
-0.371699 -1.33555 2.4875 
-0.376765 -1.35376 2.49844 
-0.384628 -1.38201 2.4875 
-0.393796 -1.41495 2.45469 
-0.402778 -1.44722 2.4 
-0 -1.4 2.4 
-0 -1.38137 2.45469 
-0 -1.38426 2.4875 
-0 -1.40312 2.49844 
-0 -1.43241 2.4875 
-0 -1.46655 2.45469 
-0 -1.5 2.4 
--0.375926 -1.35074 2.4 
--0.370922 -1.33276 2.45469 
--0.371699 -1.33555 2.4875 
--0.376765 -1.35376 2.49844 
--0.384628 -1.38201 2.4875 
--0.393796 -1.41495 2.45469 
--0.402778 -1.44722 2.4 
--0.711407 -1.21126 2.4 
--0.701938 -1.19514 2.45469 
--0.703409 -1.19764 2.4875 
--0.712995 -1.21396 2.49844 
--0.727875 -1.2393 2.4875 
--0.745225 -1.26884 2.45469 
--0.762222 -1.29778 2.4 
--0.994 -0.994 2.4 
--0.98077 -0.98077 2.45469 
--0.982824 -0.982824 2.4875 
--0.996219 -0.996219 2.49844 
--1.01701 -1.01701 2.4875 
--1.04125 -1.04125 2.45469 
--1.065 -1.065 2.4 
--1.21126 -0.711407 2.4 
--1.19514 -0.701938 2.45469 
--1.19764 -0.703409 2.4875 
--1.21396 -0.712995 2.49844 
--1.2393 -0.727875 2.4875 
--1.26884 -0.745225 2.45469 
--1.29778 -0.762222 2.4 
--1.35074 -0.375926 2.4 
--1.33276 -0.370922 2.45469 
--1.33555 -0.371699 2.4875 
--1.35376 -0.376765 2.49844 
--1.38201 -0.384628 2.4875 
--1.41495 -0.393796 2.45469 
--1.44722 -0.402778 2.4 
--1.4 0 2.4 
--1.38137 0 2.45469 
--1.38426 0 2.4875 
--1.40312 0 2.49844 
--1.43241 0 2.4875 
--1.46655 0 2.45469 
--1.5 0 2.4 
--1.35074 0.375926 2.4 
--1.33276 0.370922 2.45469 
--1.33555 0.371699 2.4875 
--1.35376 0.376765 2.49844 
--1.38201 0.384628 2.4875 
--1.41495 0.393796 2.45469 
--1.44722 0.402778 2.4 
--1.21126 0.711407 2.4 
--1.19514 0.701938 2.45469 
--1.19764 0.703409 2.4875 
--1.21396 0.712995 2.49844 
--1.2393 0.727875 2.4875 
--1.26884 0.745225 2.45469 
--1.29778 0.762222 2.4 
--0.994 0.994 2.4 
--0.98077 0.98077 2.45469 
--0.982824 0.982824 2.4875 
--0.996219 0.996219 2.49844 
--1.01701 1.01701 2.4875 
--1.04125 1.04125 2.45469 
--1.065 1.065 2.4 
--0.711407 1.21126 2.4 
--0.701938 1.19514 2.45469 
--0.703409 1.19764 2.4875 
--0.712995 1.21396 2.49844 
--0.727875 1.2393 2.4875 
--0.745225 1.26884 2.45469 
--0.762222 1.29778 2.4 
--0.375926 1.35074 2.4 
--0.370922 1.33276 2.45469 
--0.371699 1.33555 2.4875 
--0.376765 1.35376 2.49844 
--0.384628 1.38201 2.4875 
--0.393796 1.41495 2.45469 
--0.402778 1.44722 2.4 
-0 1.4 2.4 
-0 1.38137 2.45469 
-0 1.38426 2.4875 
-0 1.40312 2.49844 
-0 1.43241 2.4875 
-0 1.46655 2.45469 
-0 1.5 2.4 
-0.375926 1.35074 2.4 
-0.370922 1.33276 2.45469 
-0.371699 1.33555 2.4875 
-0.376765 1.35376 2.49844 
-0.384628 1.38201 2.4875 
-0.393796 1.41495 2.45469 
-0.402778 1.44722 2.4 
-0.711407 1.21126 2.4 
-0.701938 1.19514 2.45469 
-0.703409 1.19764 2.4875 
-0.712995 1.21396 2.49844 
-0.727875 1.2393 2.4875 
-0.745225 1.26884 2.45469 
-0.762222 1.29778 2.4 
-0.994 0.994 2.4 
-0.98077 0.98077 2.45469 
-0.982824 0.982824 2.4875 
-0.996219 0.996219 2.49844 
-1.01701 1.01701 2.4875 
-1.04125 1.04125 2.45469 
-1.065 1.065 2.4 
-1.21126 0.711407 2.4 
-1.19514 0.701938 2.45469 
-1.19764 0.703409 2.4875 
-1.21396 0.712995 2.49844 
-1.2393 0.727875 2.4875 
-1.26884 0.745225 2.45469 
-1.29778 0.762222 2.4 
-1.35074 0.375926 2.4 
-1.33276 0.370922 2.45469 
-1.33555 0.371699 2.4875 
-1.35376 0.376765 2.49844 
-1.38201 0.384628 2.4875 
-1.41495 0.393796 2.45469 
-1.44722 0.402778 2.4 
-1.62384 0 2.13785 
-1.56671 -0.436032 2.13785 
-1.74074 0 1.87778 
-1.67949 -0.467421 1.87778 
-1.84375 0 1.62187 
-1.77888 -0.495081 1.62188 
-1.92593 0 1.37222 
-1.85816 -0.517147 1.37222 
-1.98032 0 1.1309 
-1.91065 -0.531754 1.1309 
-2 0 0.9 
-1.92963 -0.537037 0.9 
-1.40492 -0.825153 2.13785 
-1.50606 -0.884554 1.87778 
-1.59519 -0.936898 1.62188 
-1.66628 -0.978656 1.37222 
-1.71335 -1.0063 1.1309 
-1.73037 -1.0163 0.9 
-1.15293 -1.15293 2.13785 
-1.23593 -1.23593 1.87778 
-1.30906 -1.30906 1.62187 
-1.36741 -1.36741 1.37222 
-1.40603 -1.40603 1.1309 
-1.42 -1.42 0.9 
-0.825153 -1.40492 2.13785 
-0.884554 -1.50606 1.87778 
-0.936898 -1.59519 1.62188 
-0.978656 -1.66628 1.37222 
-1.0063 -1.71335 1.1309 
-1.0163 -1.73037 0.9 
-0.436032 -1.56671 2.13785 
-0.467421 -1.67949 1.87778 
-0.495081 -1.77888 1.62187 
-0.517147 -1.85816 1.37222 
-0.531754 -1.91065 1.1309 
-0.537037 -1.92963 0.9 
-0 -1.62384 2.13785 
-0 -1.74074 1.87778 
-0 -1.84375 1.62187 
-0 -1.92593 1.37222 
-0 -1.98032 1.1309 
-0 -2 0.9 
--0.436032 -1.56671 2.13785 
--0.467421 -1.67949 1.87778 
--0.495081 -1.77888 1.62188 
--0.517147 -1.85816 1.37222 
--0.531754 -1.91065 1.1309 
--0.537037 -1.92963 0.9 
--0.825153 -1.40492 2.13785 
--0.884554 -1.50606 1.87778 
--0.936898 -1.59519 1.62188 
--0.978656 -1.66628 1.37222 
--1.0063 -1.71335 1.1309 
--1.0163 -1.73037 0.9 
--1.15293 -1.15293 2.13785 
--1.23593 -1.23593 1.87778 
--1.30906 -1.30906 1.62187 
--1.36741 -1.36741 1.37222 
--1.40603 -1.40603 1.1309 
--1.42 -1.42 0.9 
--1.40492 -0.825153 2.13785 
--1.50606 -0.884554 1.87778 
--1.59519 -0.936898 1.62188 
--1.66628 -0.978656 1.37222 
--1.71335 -1.0063 1.1309 
--1.73037 -1.0163 0.9 
--1.56671 -0.436032 2.13785 
--1.67949 -0.467421 1.87778 
--1.77888 -0.495081 1.62187 
--1.85816 -0.517147 1.37222 
--1.91065 -0.531754 1.1309 
--1.92963 -0.537037 0.9 
--1.62384 0 2.13785 
--1.74074 0 1.87778 
--1.84375 0 1.62187 
--1.92593 0 1.37222 
--1.98032 0 1.1309 
--2 0 0.9 
--1.56671 0.436032 2.13785 
--1.67949 0.467421 1.87778 
--1.77888 0.495081 1.62188 
--1.85816 0.517147 1.37222 
--1.91065 0.531754 1.1309 
--1.92963 0.537037 0.9 
--1.40492 0.825153 2.13785 
--1.50606 0.884554 1.87778 
--1.59519 0.936898 1.62188 
--1.66628 0.978656 1.37222 
--1.71335 1.0063 1.1309 
--1.73037 1.0163 0.9 
--1.15293 1.15293 2.13785 
--1.23593 1.23593 1.87778 
--1.30906 1.30906 1.62187 
--1.36741 1.36741 1.37222 
--1.40603 1.40603 1.1309 
--1.42 1.42 0.9 
--0.825153 1.40492 2.13785 
--0.884554 1.50606 1.87778 
--0.936898 1.59519 1.62188 
--0.978656 1.66628 1.37222 
--1.0063 1.71335 1.1309 
--1.0163 1.73037 0.9 
--0.436032 1.56671 2.13785 
--0.467421 1.67949 1.87778 
--0.495081 1.77888 1.62187 
--0.517147 1.85816 1.37222 
--0.531754 1.91065 1.1309 
--0.537037 1.92963 0.9 
-0 1.62384 2.13785 
-0 1.74074 1.87778 
-0 1.84375 1.62187 
-0 1.92593 1.37222 
-0 1.98032 1.1309 
-0 2 0.9 
-0.436032 1.56671 2.13785 
-0.467421 1.67949 1.87778 
-0.495081 1.77888 1.62188 
-0.517147 1.85816 1.37222 
-0.531754 1.91065 1.1309 
-0.537037 1.92963 0.9 
-0.825153 1.40492 2.13785 
-0.884554 1.50606 1.87778 
-0.936898 1.59519 1.62188 
-0.978656 1.66628 1.37222 
-1.0063 1.71335 1.1309 
-1.0163 1.73037 0.9 
-1.15293 1.15293 2.13785 
-1.23593 1.23593 1.87778 
-1.30906 1.30906 1.62187 
-1.36741 1.36741 1.37222 
-1.40603 1.40603 1.1309 
-1.42 1.42 0.9 
-1.40492 0.825153 2.13785 
-1.50606 0.884554 1.87778 
-1.59519 0.936898 1.62188 
-1.66628 0.978656 1.37222 
-1.71335 1.0063 1.1309 
-1.73037 1.0163 0.9 
-1.56671 0.436032 2.13785 
-1.67949 0.467421 1.87778 
-1.77888 0.495081 1.62187 
-1.85816 0.517147 1.37222 
-1.91065 0.531754 1.1309 
-1.92963 0.537037 0.9 
-1.96296 0 0.693403 
-1.8939 -0.527092 0.693403 
-1.87037 0 0.522222 
-1.80456 -0.502229 0.522222 
-1.75 0 0.384375 
-1.68843 -0.469907 0.384375 
-1.62963 0 0.277778 
-1.57229 -0.437586 0.277778 
-1.53704 0 0.200347 
-1.48296 -0.412723 0.200347 
-1.5 0 0.15 
-1.44722 -0.402778 0.15 
-1.69833 -0.997476 0.693403 
-1.61822 -0.950425 0.522222 
-1.51407 -0.889259 0.384375 
-1.40993 -0.828093 0.277778 
-1.32982 -0.781043 0.200347 
-1.29778 -0.762222 0.15 
-1.3937 -1.3937 0.693403 
-1.32796 -1.32796 0.522222 
-1.2425 -1.2425 0.384375 
-1.15704 -1.15704 0.277778 
-1.0913 -1.0913 0.200347 
-1.065 -1.065 0.15 
-0.997476 -1.69833 0.693403 
-0.950425 -1.61822 0.522222 
-0.889259 -1.51407 0.384375 
-0.828093 -1.40993 0.277778 
-0.781043 -1.32982 0.200347 
-0.762222 -1.29778 0.15 
-0.527092 -1.8939 0.693403 
-0.502229 -1.80456 0.522222 
-0.469907 -1.68843 0.384375 
-0.437586 -1.57229 0.277778 
-0.412723 -1.48296 0.200347 
-0.402778 -1.44722 0.15 
-0 -1.96296 0.693403 
-0 -1.87037 0.522222 
-0 -1.75 0.384375 
-0 -1.62963 0.277778 
-0 -1.53704 0.200347 
-0 -1.5 0.15 
--0.527092 -1.8939 0.693403 
--0.502229 -1.80456 0.522222 
--0.469907 -1.68843 0.384375 
--0.437586 -1.57229 0.277778 
--0.412723 -1.48296 0.200347 
--0.402778 -1.44722 0.15 
--0.997476 -1.69833 0.693403 
--0.950425 -1.61822 0.522222 
--0.889259 -1.51407 0.384375 
--0.828093 -1.40993 0.277778 
--0.781043 -1.32982 0.200347 
--0.762222 -1.29778 0.15 
--1.3937 -1.3937 0.693403 
--1.32796 -1.32796 0.522222 
--1.2425 -1.2425 0.384375 
--1.15704 -1.15704 0.277778 
--1.0913 -1.0913 0.200347 
--1.065 -1.065 0.15 
--1.69833 -0.997476 0.693403 
--1.61822 -0.950425 0.522222 
--1.51407 -0.889259 0.384375 
--1.40993 -0.828093 0.277778 
--1.32982 -0.781043 0.200347 
--1.29778 -0.762222 0.15 
--1.8939 -0.527092 0.693403 
--1.80456 -0.502229 0.522222 
--1.68843 -0.469907 0.384375 
--1.57229 -0.437586 0.277778 
--1.48296 -0.412723 0.200347 
--1.44722 -0.402778 0.15 
--1.96296 0 0.693403 
--1.87037 0 0.522222 
--1.75 0 0.384375 
--1.62963 0 0.277778 
--1.53704 0 0.200347 
--1.5 0 0.15 
--1.8939 0.527092 0.693403 
--1.80456 0.502229 0.522222 
--1.68843 0.469907 0.384375 
--1.57229 0.437586 0.277778 
--1.48296 0.412723 0.200347 
--1.44722 0.402778 0.15 
--1.69833 0.997476 0.693403 
--1.61822 0.950425 0.522222 
--1.51407 0.889259 0.384375 
--1.40993 0.828093 0.277778 
--1.32982 0.781043 0.200347 
--1.29778 0.762222 0.15 
--1.3937 1.3937 0.693403 
--1.32796 1.32796 0.522222 
--1.2425 1.2425 0.384375 
--1.15704 1.15704 0.277778 
--1.0913 1.0913 0.200347 
--1.065 1.065 0.15 
--0.997476 1.69833 0.693403 
--0.950425 1.61822 0.522222 
--0.889259 1.51407 0.384375 
--0.828093 1.40993 0.277778 
--0.781043 1.32982 0.200347 
--0.762222 1.29778 0.15 
--0.527092 1.8939 0.693403 
--0.502229 1.80456 0.522222 
--0.469907 1.68843 0.384375 
--0.437586 1.57229 0.277778 
--0.412723 1.48296 0.200347 
--0.402778 1.44722 0.15 
-0 1.96296 0.693403 
-0 1.87037 0.522222 
-0 1.75 0.384375 
-0 1.62963 0.277778 
-0 1.53704 0.200347 
-0 1.5 0.15 
-0.527092 1.8939 0.693403 
-0.502229 1.80456 0.522222 
-0.469907 1.68843 0.384375 
-0.437586 1.57229 0.277778 
-0.412723 1.48296 0.200347 
-0.402778 1.44722 0.15 
-0.997476 1.69833 0.693403 
-0.950425 1.61822 0.522222 
-0.889259 1.51407 0.384375 
-0.828093 1.40993 0.277778 
-0.781043 1.32982 0.200347 
-0.762222 1.29778 0.15 
-1.3937 1.3937 0.693403 
-1.32796 1.32796 0.522222 
-1.2425 1.2425 0.384375 
-1.15704 1.15704 0.277778 
-1.0913 1.0913 0.200347 
-1.065 1.065 0.15 
-1.69833 0.997476 0.693403 
-1.61822 0.950425 0.522222 
-1.51407 0.889259 0.384375 
-1.40993 0.828093 0.277778 
-1.32982 0.781043 0.200347 
-1.29778 0.762222 0.15 
-1.8939 0.527092 0.693403 
-1.80456 0.502229 0.522222 
-1.68843 0.469907 0.384375 
-1.57229 0.437586 0.277778 
-1.48296 0.412723 0.200347 
-1.44722 0.402778 0.15 
-0.605903 0 0.005903 
-0 0 0 
-0.584584 0.162696 0.005903 
-1.02222 0 0.022222 
-0.986255 0.274486 0.022222 
-1.28437 0 0.046875 
-1.23918 0.344878 0.046875 
-1.42778 0 0.077778 
-1.37754 0.383385 0.077778 
-1.48785 0 0.112847 
-1.4355 0.399515 0.112847 
-0.524218 0.307888 0.005903 
-0.884412 0.51944 0.022222 
-1.11122 0.652653 0.046875 
-1.23529 0.725523 0.077778 
-1.28726 0.756047 0.112847 
-0.430191 0.430191 0.005903 
-0.725778 0.725778 0.022222 
-0.911906 0.911906 0.046875 
-1.01372 1.01372 0.077778 
-1.05637 1.05637 0.112847 
-0.307888 0.524218 0.005903 
-0.51944 0.884412 0.022222 
-0.652653 1.11122 0.046875 
-0.725523 1.23529 0.077778 
-0.756047 1.28726 0.112847 
-0.162696 0.584584 0.005903 
-0.274486 0.986255 0.022222 
-0.344878 1.23918 0.046875 
-0.383385 1.37754 0.077778 
-0.399515 1.4355 0.112847 
-0 0.605903 0.005903 
-0 1.02222 0.022222 
-0 1.28437 0.046875 
-0 1.42778 0.077778 
-0 1.48785 0.112847 
--0.162696 0.584584 0.005903 
--0.274486 0.986255 0.022222 
--0.344878 1.23918 0.046875 
--0.383385 1.37754 0.077778 
--0.399515 1.4355 0.112847 
--0.307888 0.524218 0.005903 
--0.51944 0.884412 0.022222 
--0.652653 1.11122 0.046875 
--0.725523 1.23529 0.077778 
--0.756047 1.28726 0.112847 
--0.430191 0.430191 0.005903 
--0.725778 0.725778 0.022222 
--0.911906 0.911906 0.046875 
--1.01372 1.01372 0.077778 
--1.05637 1.05637 0.112847 
--0.524218 0.307888 0.005903 
--0.884412 0.51944 0.022222 
--1.11122 0.652653 0.046875 
--1.23529 0.725523 0.077778 
--1.28726 0.756047 0.112847 
--0.584584 0.162696 0.005903 
--0.986255 0.274486 0.022222 
--1.23918 0.344878 0.046875 
--1.37754 0.383385 0.077778 
--1.4355 0.399515 0.112847 
--0.605903 0 0.005903 
--1.02222 0 0.022222 
--1.28437 0 0.046875 
--1.42778 0 0.077778 
--1.48785 0 0.112847 
--0.584584 -0.162696 0.005903 
--0.986255 -0.274486 0.022222 
--1.23918 -0.344878 0.046875 
--1.37754 -0.383385 0.077778 
--1.4355 -0.399515 0.112847 
--0.524218 -0.307888 0.005903 
--0.884412 -0.51944 0.022222 
--1.11122 -0.652653 0.046875 
--1.23529 -0.725523 0.077778 
--1.28726 -0.756047 0.112847 
--0.430191 -0.430191 0.005903 
--0.725778 -0.725778 0.022222 
--0.911906 -0.911906 0.046875 
--1.01372 -1.01372 0.077778 
--1.05637 -1.05637 0.112847 
--0.307888 -0.524218 0.005903 
--0.51944 -0.884412 0.022222 
--0.652653 -1.11122 0.046875 
--0.725523 -1.23529 0.077778 
--0.756047 -1.28726 0.112847 
--0.162696 -0.584584 0.005903 
--0.274486 -0.986255 0.022222 
--0.344878 -1.23918 0.046875 
--0.383385 -1.37754 0.077778 
--0.399515 -1.4355 0.112847 
-0 -0.605903 0.005903 
-0 -1.02222 0.022222 
-0 -1.28437 0.046875 
-0 -1.42778 0.077778 
-0 -1.48785 0.112847 
-0.162696 -0.584584 0.005903 
-0.274486 -0.986255 0.022222 
-0.344878 -1.23918 0.046875 
-0.383385 -1.37754 0.077778 
-0.399515 -1.4355 0.112847 
-0.307888 -0.524218 0.005903 
-0.51944 -0.884412 0.022222 
-0.652653 -1.11122 0.046875 
-0.725523 -1.23529 0.077778 
-0.756047 -1.28726 0.112847 
-0.430191 -0.430191 0.005903 
-0.725778 -0.725778 0.022222 
-0.911906 -0.911906 0.046875 
-1.01372 -1.01372 0.077778 
-1.05637 -1.05637 0.112847 
-0.524218 -0.307888 0.005903 
-0.884412 -0.51944 0.022222 
-1.11122 -0.652653 0.046875 
-1.23529 -0.725523 0.077778 
-1.28726 -0.756047 0.112847 
-0.584584 -0.162696 0.005903 
-0.986255 -0.274486 0.022222 
-1.23918 -0.344878 0.046875 
-1.37754 -0.383385 0.077778 
-1.4355 -0.399515 0.112847 
-0.2 0 2.7 
-0.171296 0 2.78542 
-0.165279 -0.046045 2.78542 
-0.192963 -0.053704 2.7 
-0.148234 -0.087106 2.78542 
-0.173037 -0.10163 2.7 
-0.121672 -0.121672 2.78542 
-0.142 -0.142 2.7 
-0.087106 -0.148234 2.78542 
-0.10163 -0.173037 2.7 
-0.046045 -0.165279 2.78542 
-0.053704 -0.192963 2.7 
-0 -0.171296 2.78542 
-0 -0.2 2.7 
--0.046045 -0.165279 2.78542 
--0.053704 -0.192963 2.7 
--0.087106 -0.148234 2.78542 
--0.10163 -0.173037 2.7 
--0.121672 -0.121672 2.78542 
--0.142 -0.142 2.7 
--0.148234 -0.087106 2.78542 
--0.173037 -0.10163 2.7 
--0.165279 -0.046045 2.78542 
--0.192963 -0.053704 2.7 
--0.171296 0 2.78542 
--0.2 0 2.7 
--0.165279 0.046045 2.78542 
--0.192963 0.053704 2.7 
--0.148234 0.087106 2.78542 
--0.173037 0.10163 2.7 
--0.121672 0.121672 2.78542 
--0.142 0.142 2.7 
--0.087106 0.148234 2.78542 
--0.10163 0.173037 2.7 
--0.046045 0.165279 2.78542 
--0.053704 0.192963 2.7 
-0 0.171296 2.78542 
-0 0.2 2.7 
-0.046045 0.165279 2.78542 
-0.053704 0.192963 2.7 
-0.087106 0.148234 2.78542 
-0.10163 0.173037 2.7 
-0.121672 0.121672 2.78542 
-0.142 0.142 2.7 
-0.148234 0.087106 2.78542 
-0.173037 0.10163 2.7 
-0.165279 0.046045 2.78542 
-0.192963 0.053704 2.7 
-0.350926 0 2.63611 
-0.338579 -0.09423 2.63611 
-0.574074 0 2.58889 
-0.553875 -0.15415 2.58889 
-0.825 0 2.55 
-0.795972 -0.221528 2.55 
-1.05926 0 2.51111 
-1.02199 -0.284431 2.51111 
-1.23241 0 2.46389 
-1.18904 -0.330924 2.46389 
-1.3 0 2.4 
-1.25426 -0.349074 2.4 
-0.303616 -0.178322 2.63611 
-0.49668 -0.291715 2.58889 
-0.713778 -0.419222 2.55 
-0.916455 -0.538261 2.51111 
-1.06626 -0.626246 2.46389 
-1.12474 -0.660593 2.4 
-0.249157 -0.249157 2.63611 
-0.407593 -0.407593 2.58889 
-0.58575 -0.58575 2.55 
-0.752074 -0.752074 2.51111 
-0.875009 -0.875009 2.46389 
-0.923 -0.923 2.4 
-0.178322 -0.303616 2.63611 
-0.291715 -0.49668 2.58889 
-0.419222 -0.713778 2.55 
-0.538261 -0.916455 2.51111 
-0.626246 -1.06626 2.46389 
-0.660593 -1.12474 2.4 
-0.09423 -0.338579 2.63611 
-0.15415 -0.553875 2.58889 
-0.221528 -0.795972 2.55 
-0.284431 -1.02199 2.51111 
-0.330924 -1.18904 2.46389 
-0.349074 -1.25426 2.4 
-0 -0.350926 2.63611 
-0 -0.574074 2.58889 
-0 -0.825 2.55 
-0 -1.05926 2.51111 
-0 -1.23241 2.46389 
-0 -1.3 2.4 
--0.09423 -0.338579 2.63611 
--0.15415 -0.553875 2.58889 
--0.221528 -0.795972 2.55 
--0.284431 -1.02199 2.51111 
--0.330924 -1.18904 2.46389 
--0.349074 -1.25426 2.4 
--0.178322 -0.303616 2.63611 
--0.291715 -0.49668 2.58889 
--0.419222 -0.713778 2.55 
--0.538261 -0.916455 2.51111 
--0.626246 -1.06626 2.46389 
--0.660593 -1.12474 2.4 
--0.249157 -0.249157 2.63611 
--0.407593 -0.407593 2.58889 
--0.58575 -0.58575 2.55 
--0.752074 -0.752074 2.51111 
--0.875009 -0.875009 2.46389 
--0.923 -0.923 2.4 
--0.303616 -0.178322 2.63611 
--0.49668 -0.291715 2.58889 
--0.713778 -0.419222 2.55 
--0.916455 -0.538261 2.51111 
--1.06626 -0.626246 2.46389 
--1.12474 -0.660593 2.4 
--0.338579 -0.09423 2.63611 
--0.553875 -0.15415 2.58889 
--0.795972 -0.221528 2.55 
--1.02199 -0.284431 2.51111 
--1.18904 -0.330924 2.46389 
--1.25426 -0.349074 2.4 
--0.350926 0 2.63611 
--0.574074 0 2.58889 
--0.825 0 2.55 
--1.05926 0 2.51111 
--1.23241 0 2.46389 
--1.3 0 2.4 
--0.338579 0.09423 2.63611 
--0.553875 0.15415 2.58889 
--0.795972 0.221528 2.55 
--1.02199 0.284431 2.51111 
--1.18904 0.330924 2.46389 
--1.25426 0.349074 2.4 
--0.303616 0.178322 2.63611 
--0.49668 0.291715 2.58889 
--0.713778 0.419222 2.55 
--0.916455 0.538261 2.51111 
--1.06626 0.626246 2.46389 
--1.12474 0.660593 2.4 
--0.249157 0.249157 2.63611 
--0.407593 0.407593 2.58889 
--0.58575 0.58575 2.55 
--0.752074 0.752074 2.51111 
--0.875009 0.875009 2.46389 
--0.923 0.923 2.4 
--0.178322 0.303616 2.63611 
--0.291715 0.49668 2.58889 
--0.419222 0.713778 2.55 
--0.538261 0.916455 2.51111 
--0.626246 1.06626 2.46389 
--0.660593 1.12474 2.4 
--0.09423 0.338579 2.63611 
--0.15415 0.553875 2.58889 
--0.221528 0.795972 2.55 
--0.284431 1.02199 2.51111 
--0.330924 1.18904 2.46389 
--0.349074 1.25426 2.4 
-0 0.350926 2.63611 
-0 0.574074 2.58889 
-0 0.825 2.55 
-0 1.05926 2.51111 
-0 1.23241 2.46389 
-0 1.3 2.4 
-0.09423 0.338579 2.63611 
-0.15415 0.553875 2.58889 
-0.221528 0.795972 2.55 
-0.284431 1.02199 2.51111 
-0.330924 1.18904 2.46389 
-0.349074 1.25426 2.4 
-0.178322 0.303616 2.63611 
-0.291715 0.49668 2.58889 
-0.419222 0.713778 2.55 
-0.538261 0.916455 2.51111 
-0.626246 1.06626 2.46389 
-0.660593 1.12474 2.4 
-0.249157 0.249157 2.63611 
-0.407593 0.407593 2.58889 
-0.58575 0.58575 2.55 
-0.752074 0.752074 2.51111 
-0.875009 0.875009 2.46389 
-0.923 0.923 2.4 
-0.303616 0.178322 2.63611 
-0.49668 0.291715 2.58889 
-0.713778 0.419222 2.55 
-0.916455 0.538261 2.51111 
-1.06626 0.626246 2.46389 
-1.12474 0.660593 2.4 
-0.338579 0.09423 2.63611 
-0.553875 0.15415 2.58889 
-0.795972 0.221528 2.55 
-1.02199 0.284431 2.51111 
-1.18904 0.330924 2.46389 
-1.25426 0.349074 2.4 
--1.92454 0 2.02396 
--1.6 0 2.025 
--1.59259 -0.125 2.04167 
--1.92704 -0.125 2.04055 
--2.1963 0 2.01667 
--2.20645 -0.125 2.03272 
--2.4125 0 1.99687 
--2.42824 -0.125 2.01146 
--2.57037 0 1.95833 
--2.58985 -0.125 1.97006 
--2.66713 0 1.89479 
--2.6887 -0.125 1.90181 
--2.7 0 1.8 
--2.72222 -0.125 1.8 
--1.57407 -0.2 2.08333 
--1.9333 -0.2 2.08202 
--2.23182 -0.2 2.07284 
--2.46759 -0.2 2.04792 
--2.63855 -0.2 1.99938 
--2.74263 -0.2 1.91937 
--2.77778 -0.2 1.8 
--1.55 -0.225 2.1375 
--1.94144 -0.225 2.13594 
--2.26481 -0.225 2.125 
--2.51875 -0.225 2.09531 
--2.70185 -0.225 2.0375 
--2.81273 -0.225 1.94219 
--2.85 -0.225 1.8 
--1.52593 -0.2 2.19167 
--1.94957 -0.2 2.18985 
--2.29781 -0.2 2.17716 
--2.56991 -0.2 2.14271 
--2.76516 -0.2 2.07562 
--2.88284 -0.2 1.96501 
--2.92222 -0.2 1.8 
--1.50741 -0.125 2.23333 
--1.95583 -0.125 2.23133 
--2.32318 -0.125 2.21728 
--2.60926 -0.125 2.17917 
--2.81385 -0.125 2.10494 
--2.93676 -0.125 1.98256 
--2.97778 -0.125 1.8 
--1.5 0 2.25 
--1.95833 0 2.24792 
--2.33333 0 2.23333 
--2.625 0 2.19375 
--2.83333 0 2.11667 
--2.95833 0 1.98958 
--3 0 1.8 
--1.50741 0.125 2.23333 
--1.95583 0.125 2.23133 
--2.32318 0.125 2.21728 
--2.60926 0.125 2.17917 
--2.81385 0.125 2.10494 
--2.93676 0.125 1.98256 
--2.97778 0.125 1.8 
--1.52593 0.2 2.19167 
--1.94957 0.2 2.18985 
--2.29781 0.2 2.17716 
--2.56991 0.2 2.14271 
--2.76516 0.2 2.07562 
--2.88284 0.2 1.96501 
--2.92222 0.2 1.8 
--1.55 0.225 2.1375 
--1.94144 0.225 2.13594 
--2.26481 0.225 2.125 
--2.51875 0.225 2.09531 
--2.70185 0.225 2.0375 
--2.81273 0.225 1.94219 
--2.85 0.225 1.8 
--1.57407 0.2 2.08333 
--1.9333 0.2 2.08202 
--2.23182 0.2 2.07284 
--2.46759 0.2 2.04792 
--2.63855 0.2 1.99938 
--2.74263 0.2 1.91937 
--2.77778 0.2 1.8 
--1.59259 0.125 2.04167 
--1.92704 0.125 2.04055 
--2.20645 0.125 2.03272 
--2.42824 0.125 2.01146 
--2.58985 0.125 1.97006 
--2.6887 0.125 1.90181 
--2.72222 0.125 1.8 
--2.68287 0 1.67083 
--2.70418 -0.125 1.66398 
--2.62963 0 1.51667 
--2.64829 -0.125 1.50535 
--2.5375 0 1.35 
--2.55185 -0.125 1.33576 
--2.4037 0 1.18333 
--2.41221 -0.125 1.16687 
--2.22546 0 1.02917 
--2.22668 -0.125 1.01033 
--1.99259 -0.125 0.877778 
--2.75747 -0.2 1.64684 
--2.69492 -0.2 1.47706 
--2.58773 -0.2 1.30017 
--2.43347 -0.2 1.12572 
--2.22972 -0.2 0.963227 
--1.97407 -0.2 0.822222 
--2.82674 -0.225 1.62457 
--2.75556 -0.225 1.44028 
--2.63437 -0.225 1.25391 
--2.46111 -0.225 1.07222 
--2.23368 -0.225 0.901997 
--1.95 -0.225 0.75 
--2.896 -0.2 1.60229 
--2.81619 -0.2 1.4035 
--2.68102 -0.2 1.20764 
--2.48875 -0.2 1.01872 
--2.23764 -0.2 0.840766 
--1.92593 -0.2 0.677778 
--2.94929 -0.125 1.58515 
--2.86283 -0.125 1.37521 
--2.7169 -0.125 1.17205 
--2.51001 -0.125 0.977572 
--2.24068 -0.125 0.793666 
--1.90741 -0.125 0.622222 
--2.9706 0 1.5783 
--2.88148 0 1.36389 
--2.73125 0 1.15781 
--2.51852 0 0.961111 
--2.2419 0 0.774826 
--1.9 0 0.6 
--2.94929 0.125 1.58515 
--2.86283 0.125 1.37521 
--2.7169 0.125 1.17205 
--2.51001 0.125 0.977572 
--2.24068 0.125 0.793666 
--1.90741 0.125 0.622222 
--2.896 0.2 1.60229 
--2.81619 0.2 1.4035 
--2.68102 0.2 1.20764 
--2.48875 0.2 1.01872 
--2.23764 0.2 0.840766 
--1.92593 0.2 0.677778 
--2.82674 0.225 1.62457 
--2.75556 0.225 1.44028 
--2.63437 0.225 1.25391 
--2.46111 0.225 1.07222 
--2.23368 0.225 0.901997 
--1.95 0.225 0.75 
--2.75747 0.2 1.64684 
--2.69492 0.2 1.47706 
--2.58773 0.2 1.30017 
--2.43347 0.2 1.12572 
--2.22972 0.2 0.963227 
--1.97407 0.2 0.822222 
--2.70418 0.125 1.66398 
--2.64829 0.125 1.50535 
--2.55185 0.125 1.33576 
--2.41221 0.125 1.16687 
--2.22668 0.125 1.01033 
--1.99259 0.125 0.877778 
-2.0588 0 1.47639 
-1.7 0 1.425 
-1.7 -0.275 1.36389 
-2.07238 -0.262346 1.42521 
-2.27037 0 1.61111 
-2.29012 -0.23071 1.57202 
-2.3875 0 1.8 
-2.40972 -0.189583 1.77361 
-2.46296 0 2.01389 
-2.48765 -0.148457 1.99928 
-2.54954 0 2.22361 
-2.5804 -0.116821 2.21831 
-2.7 0 2.4 
-2.74444 -0.104167 2.4 
-1.7 -0.44 1.21111 
-2.10633 -0.419753 1.29725 
-2.33951 -0.369136 1.47428 
-2.46528 -0.303333 1.70764 
-2.54938 -0.237531 1.96276 
-2.65756 -0.186914 2.20507 
-2.85556 -0.166667 2.4 
-1.7 -0.495 1.0125 
-2.15046 -0.472222 1.1309 
-2.4037 -0.415278 1.34722 
-2.5375 -0.34125 1.62187 
-2.62963 -0.267222 1.91528 
-2.75787 -0.210278 2.18785 
-3 -0.1875 2.4 
-1.7 -0.44 0.813889 
-2.1946 -0.419753 0.964558 
-2.4679 -0.369136 1.22016 
-2.60972 -0.303333 1.53611 
-2.70988 -0.237531 1.8678 
-2.85818 -0.186914 2.17063 
-3.14444 -0.166667 2.4 
-1.7 -0.275 0.661111 
-2.22855 -0.262346 0.8366 
-2.51728 -0.23071 1.12243 
-2.66528 -0.189583 1.47014 
-2.7716 -0.148457 1.83128 
-2.93534 -0.116821 2.15738 
-3.25556 -0.104167 2.4 
-1.7 0 0.6 
-2.24213 0 0.785417 
-2.53704 0 1.08333 
-2.6875 0 1.44375 
-2.7963 0 1.81667 
-2.9662 0 2.15208 
-3.3 0 2.4 
-1.7 0.275 0.661111 
-2.22855 0.262346 0.8366 
-2.51728 0.23071 1.12243 
-2.66528 0.189583 1.47014 
-2.7716 0.148457 1.83128 
-2.93534 0.116821 2.15738 
-3.25556 0.104167 2.4 
-1.7 0.44 0.813889 
-2.1946 0.419753 0.964558 
-2.4679 0.369136 1.22016 
-2.60972 0.303333 1.53611 
-2.70988 0.237531 1.8678 
-2.85818 0.186914 2.17063 
-3.14444 0.166667 2.4 
-1.7 0.495 1.0125 
-2.15046 0.472222 1.1309 
-2.4037 0.415278 1.34722 
-2.5375 0.34125 1.62187 
-2.62963 0.267222 1.91528 
-2.75787 0.210278 2.18785 
-3 0.1875 2.4 
-1.7 0.44 1.21111 
-2.10633 0.419753 1.29725 
-2.33951 0.369136 1.47428 
-2.46528 0.303333 1.70764 
-2.54938 0.237531 1.96276 
-2.65756 0.186914 2.20507 
-2.85556 0.166667 2.4 
-1.7 0.275 1.36389 
-2.07238 0.262346 1.42521 
-2.29012 0.23071 1.57202 
-2.40972 0.189583 1.77361 
-2.48765 0.148457 1.99928 
-2.5804 0.116821 2.21831 
-2.74444 0.104167 2.4 
-2.74907 0 2.43125 
-2.79641 -0.101032 2.43193 
-2.79259 0 2.45 
-2.83978 -0.092978 2.45123 
-2.825 0 2.45625 
-2.86968 -0.082031 2.45781 
-2.84074 0 2.45 
-2.88121 -0.070216 2.45154 
-2.83426 0 2.43125 
-2.86949 -0.059558 2.43231 
-2.8 0 2.4 
-2.82963 -0.052083 2.4 
-2.91474 -0.161574 2.43361 
-2.95775 -0.148148 2.45432 
-2.98137 -0.129167 2.46172 
-2.98237 -0.107407 2.4554 
-2.95756 -0.085648 2.43496 
-2.9037 -0.066667 2.4 
-3.06858 -0.181684 2.43581 
-3.11111 -0.165972 2.45833 
-3.12656 -0.142969 2.4668 
-3.11389 -0.115278 2.46042 
-3.07205 -0.085504 2.43841 
-3 -0.05625 2.4 
-3.22241 -0.16142 2.438 
-3.26447 -0.146914 2.46235 
-3.27176 -0.125 2.47187 
-3.2454 -0.097531 2.46543 
-3.18654 -0.066358 2.44186 
-3.0963 -0.033333 2.4 
-3.34075 -0.100839 2.43969 
-3.38244 -0.091435 2.46543 
-3.38345 -0.076823 2.47578 
-3.34657 -0.05787 2.46929 
-3.27461 -0.035446 2.44451 
-3.17037 -0.010417 2.4 
-3.38808 0 2.44036 
-3.42963 0 2.46667 
-3.42813 0 2.47734 
-3.38704 0 2.47083 
-3.30984 0 2.44557 
-3.2 0 2.4 
-3.34075 0.10108 2.43969 
-3.38244 0.093364 2.46543 
-3.38345 0.083333 2.47578 
-3.34657 0.073303 2.46929 
-3.27461 0.065586 2.44451 
-3.17037 0.0625 2.4 
-3.22241 0.161728 2.438 
-3.26447 0.149383 2.46235 
-3.27176 0.133333 2.47187 
-3.2454 0.117284 2.46543 
-3.18654 0.104938 2.44186 
-3.0963 0.1 2.4 
-3.06858 0.181944 2.43581 
-3.11111 0.168056 2.45833 
-3.12656 0.15 2.4668 
-3.11389 0.131944 2.46042 
-3.07205 0.118056 2.43841 
-3 0.1125 2.4 
-2.91474 0.161728 2.43361 
-2.95775 0.149383 2.45432 
-2.98137 0.133333 2.46172 
-2.98237 0.117284 2.4554 
-2.95756 0.104938 2.43496 
-2.9037 0.1 2.4 
-2.79641 0.10108 2.43193 
-2.83978 0.093364 2.45123 
-2.86968 0.083333 2.45781 
-2.88121 0.073303 2.45154 
-2.86949 0.065586 2.43231 
-2.82963 0.0625 2.4 
-0.278704 0 3.12708 
-0 0 3.15 
-0.268946 -0.075078 3.12708 
-0.362963 0 3.06667 
-0.350254 -0.097771 3.06667 
-0.325 0 2.98125 
-0.313617 -0.087529 2.98125 
-0.237037 0 2.88333 
-0.228728 -0.063803 2.88333 
-0.241285 -0.141931 3.12708 
-0.314228 -0.184834 3.06667 
-0.281352 -0.165481 2.98125 
-0.20518 -0.120647 2.88333 
-0.19814 -0.19814 3.12708 
-0.258037 -0.258037 3.06667 
-0.231031 -0.231031 2.98125 
-0.168463 -0.168463 2.88333 
-0.141931 -0.241285 3.12708 
-0.184834 -0.314228 3.06667 
-0.165481 -0.281352 2.98125 
-0.120647 -0.20518 2.88333 
-0.075078 -0.268946 3.12708 
-0.097771 -0.350254 3.06667 
-0.087529 -0.313617 2.98125 
-0.063803 -0.228728 2.88333 
-0 -0.278704 3.12708 
-0 -0.362963 3.06667 
-0 -0.325 2.98125 
-0 -0.237037 2.88333 
--0.075078 -0.268946 3.12708 
--0.097771 -0.350254 3.06667 
--0.087529 -0.313617 2.98125 
--0.063803 -0.228728 2.88333 
--0.141931 -0.241285 3.12708 
--0.184834 -0.314228 3.06667 
--0.165481 -0.281352 2.98125 
--0.120647 -0.20518 2.88333 
--0.19814 -0.19814 3.12708 
--0.258037 -0.258037 3.06667 
--0.231031 -0.231031 2.98125 
--0.168463 -0.168463 2.88333 
--0.241285 -0.141931 3.12708 
--0.314228 -0.184834 3.06667 
--0.281352 -0.165481 2.98125 
--0.20518 -0.120647 2.88333 
--0.268946 -0.075078 3.12708 
--0.350254 -0.097771 3.06667 
--0.313617 -0.087529 2.98125 
--0.228728 -0.063803 2.88333 
--0.278704 0 3.12708 
--0.362963 0 3.06667 
--0.325 0 2.98125 
--0.237037 0 2.88333 
--0.268946 0.075078 3.12708 
--0.350254 0.097771 3.06667 
--0.313617 0.087529 2.98125 
--0.228728 0.063803 2.88333 
--0.241285 0.141931 3.12708 
--0.314228 0.184834 3.06667 
--0.281352 0.165481 2.98125 
--0.20518 0.120647 2.88333 
--0.19814 0.19814 3.12708 
--0.258037 0.258037 3.06667 
--0.231031 0.231031 2.98125 
--0.168463 0.168463 2.88333 
--0.141931 0.241285 3.12708 
--0.184834 0.314228 3.06667 
--0.165481 0.281352 2.98125 
--0.120647 0.20518 2.88333 
--0.075078 0.268946 3.12708 
--0.097771 0.350254 3.06667 
--0.087529 0.313617 2.98125 
--0.063803 0.228728 2.88333 
-0 0.278704 3.12708 
-0 0.362963 3.06667 
-0 0.325 2.98125 
-0 0.237037 2.88333 
-0.075078 0.268946 3.12708 
-0.097771 0.350254 3.06667 
-0.087529 0.313617 2.98125 
-0.063803 0.228728 2.88333 
-0.141931 0.241285 3.12708 
-0.184834 0.314228 3.06667 
-0.165481 0.281352 2.98125 
-0.120647 0.20518 2.88333 
-0.19814 0.19814 3.12708 
-0.258037 0.258037 3.06667 
-0.231031 0.231031 2.98125 
-0.168463 0.168463 2.88333 
-0.241285 0.141931 3.12708 
-0.314228 0.184834 3.06667 
-0.281352 0.165481 2.98125 
-0.20518 0.120647 2.88333 
-0.268946 0.075078 3.12708 
-0.350254 0.097771 3.06667 
-0.313617 0.087529 2.98125 
-0.228728 0.063803 2.88333 
-3 0 1 2 
-3 0 2 3 
-3 4 0 3 
-3 4 3 5 
-3 6 4 5 
-3 6 5 7 
-3 8 6 7 
-3 8 7 9 
-3 10 8 9 
-3 10 9 11 
-3 12 10 11 
-3 12 11 13 
-3 3 2 14 
-3 3 14 15 
-3 5 3 15 
-3 5 15 16 
-3 7 5 16 
-3 7 16 17 
-3 9 7 17 
-3 9 17 18 
-3 11 9 18 
-3 11 18 19 
-3 13 11 19 
-3 13 19 20 
-3 15 14 21 
-3 15 21 22 
-3 16 15 22 
-3 16 22 23 
-3 17 16 23 
-3 17 23 24 
-3 18 17 24 
-3 18 24 25 
-3 19 18 25 
-3 19 25 26 
-3 20 19 26 
-3 20 26 27 
-3 22 21 28 
-3 22 28 29 
-3 23 22 29 
-3 23 29 30 
-3 24 23 30 
-3 24 30 31 
-3 25 24 31 
-3 25 31 32 
-3 26 25 32 
-3 26 32 33 
-3 27 26 33 
-3 27 33 34 
-3 29 28 35 
-3 29 35 36 
-3 30 29 36 
-3 30 36 37 
-3 31 30 37 
-3 31 37 38 
-3 32 31 38 
-3 32 38 39 
-3 33 32 39 
-3 33 39 40 
-3 34 33 40 
-3 34 40 41 
-3 36 35 42 
-3 36 42 43 
-3 37 36 43 
-3 37 43 44 
-3 38 37 44 
-3 38 44 45 
-3 39 38 45 
-3 39 45 46 
-3 40 39 46 
-3 40 46 47 
-3 41 40 47 
-3 41 47 48 
-3 43 42 49 
-3 43 49 50 
-3 44 43 50 
-3 44 50 51 
-3 45 44 51 
-3 45 51 52 
-3 46 45 52 
-3 46 52 53 
-3 47 46 53 
-3 47 53 54 
-3 48 47 54 
-3 48 54 55 
-3 50 49 56 
-3 50 56 57 
-3 51 50 57 
-3 51 57 58 
-3 52 51 58 
-3 52 58 59 
-3 53 52 59 
-3 53 59 60 
-3 54 53 60 
-3 54 60 61 
-3 55 54 61 
-3 55 61 62 
-3 57 56 63 
-3 57 63 64 
-3 58 57 64 
-3 58 64 65 
-3 59 58 65 
-3 59 65 66 
-3 60 59 66 
-3 60 66 67 
-3 61 60 67 
-3 61 67 68 
-3 62 61 68 
-3 62 68 69 
-3 64 63 70 
-3 64 70 71 
-3 65 64 71 
-3 65 71 72 
-3 66 65 72 
-3 66 72 73 
-3 67 66 73 
-3 67 73 74 
-3 68 67 74 
-3 68 74 75 
-3 69 68 75 
-3 69 75 76 
-3 71 70 77 
-3 71 77 78 
-3 72 71 78 
-3 72 78 79 
-3 73 72 79 
-3 73 79 80 
-3 74 73 80 
-3 74 80 81 
-3 75 74 81 
-3 75 81 82 
-3 76 75 82 
-3 76 82 83 
-3 78 77 84 
-3 78 84 85 
-3 79 78 85 
-3 79 85 86 
-3 80 79 86 
-3 80 86 87 
-3 81 80 87 
-3 81 87 88 
-3 82 81 88 
-3 82 88 89 
-3 83 82 89 
-3 83 89 90 
-3 85 84 91 
-3 85 91 92 
-3 86 85 92 
-3 86 92 93 
-3 87 86 93 
-3 87 93 94 
-3 88 87 94 
-3 88 94 95 
-3 89 88 95 
-3 89 95 96 
-3 90 89 96 
-3 90 96 97 
-3 92 91 98 
-3 92 98 99 
-3 93 92 99 
-3 93 99 100 
-3 94 93 100 
-3 94 100 101 
-3 95 94 101 
-3 95 101 102 
-3 96 95 102 
-3 96 102 103 
-3 97 96 103 
-3 97 103 104 
-3 99 98 105 
-3 99 105 106 
-3 100 99 106 
-3 100 106 107 
-3 101 100 107 
-3 101 107 108 
-3 102 101 108 
-3 102 108 109 
-3 103 102 109 
-3 103 109 110 
-3 104 103 110 
-3 104 110 111 
-3 106 105 112 
-3 106 112 113 
-3 107 106 113 
-3 107 113 114 
-3 108 107 114 
-3 108 114 115 
-3 109 108 115 
-3 109 115 116 
-3 110 109 116 
-3 110 116 117 
-3 111 110 117 
-3 111 117 118 
-3 113 112 119 
-3 113 119 120 
-3 114 113 120 
-3 114 120 121 
-3 115 114 121 
-3 115 121 122 
-3 116 115 122 
-3 116 122 123 
-3 117 116 123 
-3 117 123 124 
-3 118 117 124 
-3 118 124 125 
-3 120 119 126 
-3 120 126 127 
-3 121 120 127 
-3 121 127 128 
-3 122 121 128 
-3 122 128 129 
-3 123 122 129 
-3 123 129 130 
-3 124 123 130 
-3 124 130 131 
-3 125 124 131 
-3 125 131 132 
-3 127 126 133 
-3 127 133 134 
-3 128 127 134 
-3 128 134 135 
-3 129 128 135 
-3 129 135 136 
-3 130 129 136 
-3 130 136 137 
-3 131 130 137 
-3 131 137 138 
-3 132 131 138 
-3 132 138 139 
-3 134 133 140 
-3 134 140 141 
-3 135 134 141 
-3 135 141 142 
-3 136 135 142 
-3 136 142 143 
-3 137 136 143 
-3 137 143 144 
-3 138 137 144 
-3 138 144 145 
-3 139 138 145 
-3 139 145 146 
-3 141 140 147 
-3 141 147 148 
-3 142 141 148 
-3 142 148 149 
-3 143 142 149 
-3 143 149 150 
-3 144 143 150 
-3 144 150 151 
-3 145 144 151 
-3 145 151 152 
-3 146 145 152 
-3 146 152 153 
-3 148 147 154 
-3 148 154 155 
-3 149 148 155 
-3 149 155 156 
-3 150 149 156 
-3 150 156 157 
-3 151 150 157 
-3 151 157 158 
-3 152 151 158 
-3 152 158 159 
-3 153 152 159 
-3 153 159 160 
-3 155 154 161 
-3 155 161 162 
-3 156 155 162 
-3 156 162 163 
-3 157 156 163 
-3 157 163 164 
-3 158 157 164 
-3 158 164 165 
-3 159 158 165 
-3 159 165 166 
-3 160 159 166 
-3 160 166 167 
-3 162 161 1 
-3 162 1 0 
-3 163 162 0 
-3 163 0 4 
-3 164 163 4 
-3 164 4 6 
-3 165 164 6 
-3 165 6 8 
-3 166 165 8 
-3 166 8 10 
-3 167 166 10 
-3 167 10 12 
-3 168 12 13 
-3 168 13 169 
-3 170 168 169 
-3 170 169 171 
-3 172 170 171 
-3 172 171 173 
-3 174 172 173 
-3 174 173 175 
-3 176 174 175 
-3 176 175 177 
-3 178 176 177 
-3 178 177 179 
-3 169 13 20 
-3 169 20 180 
-3 171 169 180 
-3 171 180 181 
-3 173 171 181 
-3 173 181 182 
-3 175 173 182 
-3 175 182 183 
-3 177 175 183 
-3 177 183 184 
-3 179 177 184 
-3 179 184 185 
-3 180 20 27 
-3 180 27 186 
-3 181 180 186 
-3 181 186 187 
-3 182 181 187 
-3 182 187 188 
-3 183 182 188 
-3 183 188 189 
-3 184 183 189 
-3 184 189 190 
-3 185 184 190 
-3 185 190 191 
-3 186 27 34 
-3 186 34 192 
-3 187 186 192 
-3 187 192 193 
-3 188 187 193 
-3 188 193 194 
-3 189 188 194 
-3 189 194 195 
-3 190 189 195 
-3 190 195 196 
-3 191 190 196 
-3 191 196 197 
-3 192 34 41 
-3 192 41 198 
-3 193 192 198 
-3 193 198 199 
-3 194 193 199 
-3 194 199 200 
-3 195 194 200 
-3 195 200 201 
-3 196 195 201 
-3 196 201 202 
-3 197 196 202 
-3 197 202 203 
-3 198 41 48 
-3 198 48 204 
-3 199 198 204 
-3 199 204 205 
-3 200 199 205 
-3 200 205 206 
-3 201 200 206 
-3 201 206 207 
-3 202 201 207 
-3 202 207 208 
-3 203 202 208 
-3 203 208 209 
-3 204 48 55 
-3 204 55 210 
-3 205 204 210 
-3 205 210 211 
-3 206 205 211 
-3 206 211 212 
-3 207 206 212 
-3 207 212 213 
-3 208 207 213 
-3 208 213 214 
-3 209 208 214 
-3 209 214 215 
-3 210 55 62 
-3 210 62 216 
-3 211 210 216 
-3 211 216 217 
-3 212 211 217 
-3 212 217 218 
-3 213 212 218 
-3 213 218 219 
-3 214 213 219 
-3 214 219 220 
-3 215 214 220 
-3 215 220 221 
-3 216 62 69 
-3 216 69 222 
-3 217 216 222 
-3 217 222 223 
-3 218 217 223 
-3 218 223 224 
-3 219 218 224 
-3 219 224 225 
-3 220 219 225 
-3 220 225 226 
-3 221 220 226 
-3 221 226 227 
-3 222 69 76 
-3 222 76 228 
-3 223 222 228 
-3 223 228 229 
-3 224 223 229 
-3 224 229 230 
-3 225 224 230 
-3 225 230 231 
-3 226 225 231 
-3 226 231 232 
-3 227 226 232 
-3 227 232 233 
-3 228 76 83 
-3 228 83 234 
-3 229 228 234 
-3 229 234 235 
-3 230 229 235 
-3 230 235 236 
-3 231 230 236 
-3 231 236 237 
-3 232 231 237 
-3 232 237 238 
-3 233 232 238 
-3 233 238 239 
-3 234 83 90 
-3 234 90 240 
-3 235 234 240 
-3 235 240 241 
-3 236 235 241 
-3 236 241 242 
-3 237 236 242 
-3 237 242 243 
-3 238 237 243 
-3 238 243 244 
-3 239 238 244 
-3 239 244 245 
-3 240 90 97 
-3 240 97 246 
-3 241 240 246 
-3 241 246 247 
-3 242 241 247 
-3 242 247 248 
-3 243 242 248 
-3 243 248 249 
-3 244 243 249 
-3 244 249 250 
-3 245 244 250 
-3 245 250 251 
-3 246 97 104 
-3 246 104 252 
-3 247 246 252 
-3 247 252 253 
-3 248 247 253 
-3 248 253 254 
-3 249 248 254 
-3 249 254 255 
-3 250 249 255 
-3 250 255 256 
-3 251 250 256 
-3 251 256 257 
-3 252 104 111 
-3 252 111 258 
-3 253 252 258 
-3 253 258 259 
-3 254 253 259 
-3 254 259 260 
-3 255 254 260 
-3 255 260 261 
-3 256 255 261 
-3 256 261 262 
-3 257 256 262 
-3 257 262 263 
-3 258 111 118 
-3 258 118 264 
-3 259 258 264 
-3 259 264 265 
-3 260 259 265 
-3 260 265 266 
-3 261 260 266 
-3 261 266 267 
-3 262 261 267 
-3 262 267 268 
-3 263 262 268 
-3 263 268 269 
-3 264 118 125 
-3 264 125 270 
-3 265 264 270 
-3 265 270 271 
-3 266 265 271 
-3 266 271 272 
-3 267 266 272 
-3 267 272 273 
-3 268 267 273 
-3 268 273 274 
-3 269 268 274 
-3 269 274 275 
-3 270 125 132 
-3 270 132 276 
-3 271 270 276 
-3 271 276 277 
-3 272 271 277 
-3 272 277 278 
-3 273 272 278 
-3 273 278 279 
-3 274 273 279 
-3 274 279 280 
-3 275 274 280 
-3 275 280 281 
-3 276 132 139 
-3 276 139 282 
-3 277 276 282 
-3 277 282 283 
-3 278 277 283 
-3 278 283 284 
-3 279 278 284 
-3 279 284 285 
-3 280 279 285 
-3 280 285 286 
-3 281 280 286 
-3 281 286 287 
-3 282 139 146 
-3 282 146 288 
-3 283 282 288 
-3 283 288 289 
-3 284 283 289 
-3 284 289 290 
-3 285 284 290 
-3 285 290 291 
-3 286 285 291 
-3 286 291 292 
-3 287 286 292 
-3 287 292 293 
-3 288 146 153 
-3 288 153 294 
-3 289 288 294 
-3 289 294 295 
-3 290 289 295 
-3 290 295 296 
-3 291 290 296 
-3 291 296 297 
-3 292 291 297 
-3 292 297 298 
-3 293 292 298 
-3 293 298 299 
-3 294 153 160 
-3 294 160 300 
-3 295 294 300 
-3 295 300 301 
-3 296 295 301 
-3 296 301 302 
-3 297 296 302 
-3 297 302 303 
-3 298 297 303 
-3 298 303 304 
-3 299 298 304 
-3 299 304 305 
-3 300 160 167 
-3 300 167 306 
-3 301 300 306 
-3 301 306 307 
-3 302 301 307 
-3 302 307 308 
-3 303 302 308 
-3 303 308 309 
-3 304 303 309 
-3 304 309 310 
-3 305 304 310 
-3 305 310 311 
-3 306 167 12 
-3 306 12 168 
-3 307 306 168 
-3 307 168 170 
-3 308 307 170 
-3 308 170 172 
-3 309 308 172 
-3 309 172 174 
-3 310 309 174 
-3 310 174 176 
-3 311 310 176 
-3 311 176 178 
-3 312 178 179 
-3 312 179 313 
-3 314 312 313 
-3 314 313 315 
-3 316 314 315 
-3 316 315 317 
-3 318 316 317 
-3 318 317 319 
-3 320 318 319 
-3 320 319 321 
-3 322 320 321 
-3 322 321 323 
-3 313 179 185 
-3 313 185 324 
-3 315 313 324 
-3 315 324 325 
-3 317 315 325 
-3 317 325 326 
-3 319 317 326 
-3 319 326 327 
-3 321 319 327 
-3 321 327 328 
-3 323 321 328 
-3 323 328 329 
-3 324 185 191 
-3 324 191 330 
-3 325 324 330 
-3 325 330 331 
-3 326 325 331 
-3 326 331 332 
-3 327 326 332 
-3 327 332 333 
-3 328 327 333 
-3 328 333 334 
-3 329 328 334 
-3 329 334 335 
-3 330 191 197 
-3 330 197 336 
-3 331 330 336 
-3 331 336 337 
-3 332 331 337 
-3 332 337 338 
-3 333 332 338 
-3 333 338 339 
-3 334 333 339 
-3 334 339 340 
-3 335 334 340 
-3 335 340 341 
-3 336 197 203 
-3 336 203 342 
-3 337 336 342 
-3 337 342 343 
-3 338 337 343 
-3 338 343 344 
-3 339 338 344 
-3 339 344 345 
-3 340 339 345 
-3 340 345 346 
-3 341 340 346 
-3 341 346 347 
-3 342 203 209 
-3 342 209 348 
-3 343 342 348 
-3 343 348 349 
-3 344 343 349 
-3 344 349 350 
-3 345 344 350 
-3 345 350 351 
-3 346 345 351 
-3 346 351 352 
-3 347 346 352 
-3 347 352 353 
-3 348 209 215 
-3 348 215 354 
-3 349 348 354 
-3 349 354 355 
-3 350 349 355 
-3 350 355 356 
-3 351 350 356 
-3 351 356 357 
-3 352 351 357 
-3 352 357 358 
-3 353 352 358 
-3 353 358 359 
-3 354 215 221 
-3 354 221 360 
-3 355 354 360 
-3 355 360 361 
-3 356 355 361 
-3 356 361 362 
-3 357 356 362 
-3 357 362 363 
-3 358 357 363 
-3 358 363 364 
-3 359 358 364 
-3 359 364 365 
-3 360 221 227 
-3 360 227 366 
-3 361 360 366 
-3 361 366 367 
-3 362 361 367 
-3 362 367 368 
-3 363 362 368 
-3 363 368 369 
-3 364 363 369 
-3 364 369 370 
-3 365 364 370 
-3 365 370 371 
-3 366 227 233 
-3 366 233 372 
-3 367 366 372 
-3 367 372 373 
-3 368 367 373 
-3 368 373 374 
-3 369 368 374 
-3 369 374 375 
-3 370 369 375 
-3 370 375 376 
-3 371 370 376 
-3 371 376 377 
-3 372 233 239 
-3 372 239 378 
-3 373 372 378 
-3 373 378 379 
-3 374 373 379 
-3 374 379 380 
-3 375 374 380 
-3 375 380 381 
-3 376 375 381 
-3 376 381 382 
-3 377 376 382 
-3 377 382 383 
-3 378 239 245 
-3 378 245 384 
-3 379 378 384 
-3 379 384 385 
-3 380 379 385 
-3 380 385 386 
-3 381 380 386 
-3 381 386 387 
-3 382 381 387 
-3 382 387 388 
-3 383 382 388 
-3 383 388 389 
-3 384 245 251 
-3 384 251 390 
-3 385 384 390 
-3 385 390 391 
-3 386 385 391 
-3 386 391 392 
-3 387 386 392 
-3 387 392 393 
-3 388 387 393 
-3 388 393 394 
-3 389 388 394 
-3 389 394 395 
-3 390 251 257 
-3 390 257 396 
-3 391 390 396 
-3 391 396 397 
-3 392 391 397 
-3 392 397 398 
-3 393 392 398 
-3 393 398 399 
-3 394 393 399 
-3 394 399 400 
-3 395 394 400 
-3 395 400 401 
-3 396 257 263 
-3 396 263 402 
-3 397 396 402 
-3 397 402 403 
-3 398 397 403 
-3 398 403 404 
-3 399 398 404 
-3 399 404 405 
-3 400 399 405 
-3 400 405 406 
-3 401 400 406 
-3 401 406 407 
-3 402 263 269 
-3 402 269 408 
-3 403 402 408 
-3 403 408 409 
-3 404 403 409 
-3 404 409 410 
-3 405 404 410 
-3 405 410 411 
-3 406 405 411 
-3 406 411 412 
-3 407 406 412 
-3 407 412 413 
-3 408 269 275 
-3 408 275 414 
-3 409 408 414 
-3 409 414 415 
-3 410 409 415 
-3 410 415 416 
-3 411 410 416 
-3 411 416 417 
-3 412 411 417 
-3 412 417 418 
-3 413 412 418 
-3 413 418 419 
-3 414 275 281 
-3 414 281 420 
-3 415 414 420 
-3 415 420 421 
-3 416 415 421 
-3 416 421 422 
-3 417 416 422 
-3 417 422 423 
-3 418 417 423 
-3 418 423 424 
-3 419 418 424 
-3 419 424 425 
-3 420 281 287 
-3 420 287 426 
-3 421 420 426 
-3 421 426 427 
-3 422 421 427 
-3 422 427 428 
-3 423 422 428 
-3 423 428 429 
-3 424 423 429 
-3 424 429 430 
-3 425 424 430 
-3 425 430 431 
-3 426 287 293 
-3 426 293 432 
-3 427 426 432 
-3 427 432 433 
-3 428 427 433 
-3 428 433 434 
-3 429 428 434 
-3 429 434 435 
-3 430 429 435 
-3 430 435 436 
-3 431 430 436 
-3 431 436 437 
-3 432 293 299 
-3 432 299 438 
-3 433 432 438 
-3 433 438 439 
-3 434 433 439 
-3 434 439 440 
-3 435 434 440 
-3 435 440 441 
-3 436 435 441 
-3 436 441 442 
-3 437 436 442 
-3 437 442 443 
-3 438 299 305 
-3 438 305 444 
-3 439 438 444 
-3 439 444 445 
-3 440 439 445 
-3 440 445 446 
-3 441 440 446 
-3 441 446 447 
-3 442 441 447 
-3 442 447 448 
-3 443 442 448 
-3 443 448 449 
-3 444 305 311 
-3 444 311 450 
-3 445 444 450 
-3 445 450 451 
-3 446 445 451 
-3 446 451 452 
-3 447 446 452 
-3 447 452 453 
-3 448 447 453 
-3 448 453 454 
-3 449 448 454 
-3 449 454 455 
-3 450 311 178 
-3 450 178 312 
-3 451 450 312 
-3 451 312 314 
-3 452 451 314 
-3 452 314 316 
-3 453 452 316 
-3 453 316 318 
-3 454 453 318 
-3 454 318 320 
-3 455 454 320 
-3 455 320 322 
-3 456 457 458 
-3 459 456 458 
-3 459 458 460 
-3 461 459 460 
-3 461 460 462 
-3 463 461 462 
-3 463 462 464 
-3 465 463 464 
-3 465 464 466 
-3 322 465 466 
-3 322 466 455 
-3 458 457 467 
-3 460 458 467 
-3 460 467 468 
-3 462 460 468 
-3 462 468 469 
-3 464 462 469 
-3 464 469 470 
-3 466 464 470 
-3 466 470 471 
-3 455 466 471 
-3 455 471 449 
-3 467 457 472 
-3 468 467 472 
-3 468 472 473 
-3 469 468 473 
-3 469 473 474 
-3 470 469 474 
-3 470 474 475 
-3 471 470 475 
-3 471 475 476 
-3 449 471 476 
-3 449 476 443 
-3 472 457 477 
-3 473 472 477 
-3 473 477 478 
-3 474 473 478 
-3 474 478 479 
-3 475 474 479 
-3 475 479 480 
-3 476 475 480 
-3 476 480 481 
-3 443 476 481 
-3 443 481 437 
-3 477 457 482 
-3 478 477 482 
-3 478 482 483 
-3 479 478 483 
-3 479 483 484 
-3 480 479 484 
-3 480 484 485 
-3 481 480 485 
-3 481 485 486 
-3 437 481 486 
-3 437 486 431 
-3 482 457 487 
-3 483 482 487 
-3 483 487 488 
-3 484 483 488 
-3 484 488 489 
-3 485 484 489 
-3 485 489 490 
-3 486 485 490 
-3 486 490 491 
-3 431 486 491 
-3 431 491 425 
-3 487 457 492 
-3 488 487 492 
-3 488 492 493 
-3 489 488 493 
-3 489 493 494 
-3 490 489 494 
-3 490 494 495 
-3 491 490 495 
-3 491 495 496 
-3 425 491 496 
-3 425 496 419 
-3 492 457 497 
-3 493 492 497 
-3 493 497 498 
-3 494 493 498 
-3 494 498 499 
-3 495 494 499 
-3 495 499 500 
-3 496 495 500 
-3 496 500 501 
-3 419 496 501 
-3 419 501 413 
-3 497 457 502 
-3 498 497 502 
-3 498 502 503 
-3 499 498 503 
-3 499 503 504 
-3 500 499 504 
-3 500 504 505 
-3 501 500 505 
-3 501 505 506 
-3 413 501 506 
-3 413 506 407 
-3 502 457 507 
-3 503 502 507 
-3 503 507 508 
-3 504 503 508 
-3 504 508 509 
-3 505 504 509 
-3 505 509 510 
-3 506 505 510 
-3 506 510 511 
-3 407 506 511 
-3 407 511 401 
-3 507 457 512 
-3 508 507 512 
-3 508 512 513 
-3 509 508 513 
-3 509 513 514 
-3 510 509 514 
-3 510 514 515 
-3 511 510 515 
-3 511 515 516 
-3 401 511 516 
-3 401 516 395 
-3 512 457 517 
-3 513 512 517 
-3 513 517 518 
-3 514 513 518 
-3 514 518 519 
-3 515 514 519 
-3 515 519 520 
-3 516 515 520 
-3 516 520 521 
-3 395 516 521 
-3 395 521 389 
-3 517 457 522 
-3 518 517 522 
-3 518 522 523 
-3 519 518 523 
-3 519 523 524 
-3 520 519 524 
-3 520 524 525 
-3 521 520 525 
-3 521 525 526 
-3 389 521 526 
-3 389 526 383 
-3 522 457 527 
-3 523 522 527 
-3 523 527 528 
-3 524 523 528 
-3 524 528 529 
-3 525 524 529 
-3 525 529 530 
-3 526 525 530 
-3 526 530 531 
-3 383 526 531 
-3 383 531 377 
-3 527 457 532 
-3 528 527 532 
-3 528 532 533 
-3 529 528 533 
-3 529 533 534 
-3 530 529 534 
-3 530 534 535 
-3 531 530 535 
-3 531 535 536 
-3 377 531 536 
-3 377 536 371 
-3 532 457 537 
-3 533 532 537 
-3 533 537 538 
-3 534 533 538 
-3 534 538 539 
-3 535 534 539 
-3 535 539 540 
-3 536 535 540 
-3 536 540 541 
-3 371 536 541 
-3 371 541 365 
-3 537 457 542 
-3 538 537 542 
-3 538 542 543 
-3 539 538 543 
-3 539 543 544 
-3 540 539 544 
-3 540 544 545 
-3 541 540 545 
-3 541 545 546 
-3 365 541 546 
-3 365 546 359 
-3 542 457 547 
-3 543 542 547 
-3 543 547 548 
-3 544 543 548 
-3 544 548 549 
-3 545 544 549 
-3 545 549 550 
-3 546 545 550 
-3 546 550 551 
-3 359 546 551 
-3 359 551 353 
-3 547 457 552 
-3 548 547 552 
-3 548 552 553 
-3 549 548 553 
-3 549 553 554 
-3 550 549 554 
-3 550 554 555 
-3 551 550 555 
-3 551 555 556 
-3 353 551 556 
-3 353 556 347 
-3 552 457 557 
-3 553 552 557 
-3 553 557 558 
-3 554 553 558 
-3 554 558 559 
-3 555 554 559 
-3 555 559 560 
-3 556 555 560 
-3 556 560 561 
-3 347 556 561 
-3 347 561 341 
-3 557 457 562 
-3 558 557 562 
-3 558 562 563 
-3 559 558 563 
-3 559 563 564 
-3 560 559 564 
-3 560 564 565 
-3 561 560 565 
-3 561 565 566 
-3 341 561 566 
-3 341 566 335 
-3 562 457 567 
-3 563 562 567 
-3 563 567 568 
-3 564 563 568 
-3 564 568 569 
-3 565 564 569 
-3 565 569 570 
-3 566 565 570 
-3 566 570 571 
-3 335 566 571 
-3 335 571 329 
-3 567 457 572 
-3 568 567 572 
-3 568 572 573 
-3 569 568 573 
-3 569 573 574 
-3 570 569 574 
-3 570 574 575 
-3 571 570 575 
-3 571 575 576 
-3 329 571 576 
-3 329 576 323 
-3 572 457 456 
-3 573 572 456 
-3 573 456 459 
-3 574 573 459 
-3 574 459 461 
-3 575 574 461 
-3 575 461 463 
-3 576 575 463 
-3 576 463 465 
-3 323 576 465 
-3 323 465 322 
-3 577 578 579 
-3 577 579 580 
-3 580 579 581 
-3 580 581 582 
-3 582 581 583 
-3 582 583 584 
-3 584 583 585 
-3 584 585 586 
-3 586 585 587 
-3 586 587 588 
-3 588 587 589 
-3 588 589 590 
-3 590 589 591 
-3 590 591 592 
-3 592 591 593 
-3 592 593 594 
-3 594 593 595 
-3 594 595 596 
-3 596 595 597 
-3 596 597 598 
-3 598 597 599 
-3 598 599 600 
-3 600 599 601 
-3 600 601 602 
-3 602 601 603 
-3 602 603 604 
-3 604 603 605 
-3 604 605 606 
-3 606 605 607 
-3 606 607 608 
-3 608 607 609 
-3 608 609 610 
-3 610 609 611 
-3 610 611 612 
-3 612 611 613 
-3 612 613 614 
-3 614 613 615 
-3 614 615 616 
-3 616 615 617 
-3 616 617 618 
-3 618 617 619 
-3 618 619 620 
-3 620 619 621 
-3 620 621 622 
-3 622 621 623 
-3 622 623 624 
-3 624 623 578 
-3 624 578 577 
-3 625 577 580 
-3 625 580 626 
-3 627 625 626 
-3 627 626 628 
-3 629 627 628 
-3 629 628 630 
-3 631 629 630 
-3 631 630 632 
-3 633 631 632 
-3 633 632 634 
-3 635 633 634 
-3 635 634 636 
-3 626 580 582 
-3 626 582 637 
-3 628 626 637 
-3 628 637 638 
-3 630 628 638 
-3 630 638 639 
-3 632 630 639 
-3 632 639 640 
-3 634 632 640 
-3 634 640 641 
-3 636 634 641 
-3 636 641 642 
-3 637 582 584 
-3 637 584 643 
-3 638 637 643 
-3 638 643 644 
-3 639 638 644 
-3 639 644 645 
-3 640 639 645 
-3 640 645 646 
-3 641 640 646 
-3 641 646 647 
-3 642 641 647 
-3 642 647 648 
-3 643 584 586 
-3 643 586 649 
-3 644 643 649 
-3 644 649 650 
-3 645 644 650 
-3 645 650 651 
-3 646 645 651 
-3 646 651 652 
-3 647 646 652 
-3 647 652 653 
-3 648 647 653 
-3 648 653 654 
-3 649 586 588 
-3 649 588 655 
-3 650 649 655 
-3 650 655 656 
-3 651 650 656 
-3 651 656 657 
-3 652 651 657 
-3 652 657 658 
-3 653 652 658 
-3 653 658 659 
-3 654 653 659 
-3 654 659 660 
-3 655 588 590 
-3 655 590 661 
-3 656 655 661 
-3 656 661 662 
-3 657 656 662 
-3 657 662 663 
-3 658 657 663 
-3 658 663 664 
-3 659 658 664 
-3 659 664 665 
-3 660 659 665 
-3 660 665 666 
-3 661 590 592 
-3 661 592 667 
-3 662 661 667 
-3 662 667 668 
-3 663 662 668 
-3 663 668 669 
-3 664 663 669 
-3 664 669 670 
-3 665 664 670 
-3 665 670 671 
-3 666 665 671 
-3 666 671 672 
-3 667 592 594 
-3 667 594 673 
-3 668 667 673 
-3 668 673 674 
-3 669 668 674 
-3 669 674 675 
-3 670 669 675 
-3 670 675 676 
-3 671 670 676 
-3 671 676 677 
-3 672 671 677 
-3 672 677 678 
-3 673 594 596 
-3 673 596 679 
-3 674 673 679 
-3 674 679 680 
-3 675 674 680 
-3 675 680 681 
-3 676 675 681 
-3 676 681 682 
-3 677 676 682 
-3 677 682 683 
-3 678 677 683 
-3 678 683 684 
-3 679 596 598 
-3 679 598 685 
-3 680 679 685 
-3 680 685 686 
-3 681 680 686 
-3 681 686 687 
-3 682 681 687 
-3 682 687 688 
-3 683 682 688 
-3 683 688 689 
-3 684 683 689 
-3 684 689 690 
-3 685 598 600 
-3 685 600 691 
-3 686 685 691 
-3 686 691 692 
-3 687 686 692 
-3 687 692 693 
-3 688 687 693 
-3 688 693 694 
-3 689 688 694 
-3 689 694 695 
-3 690 689 695 
-3 690 695 696 
-3 691 600 602 
-3 691 602 697 
-3 692 691 697 
-3 692 697 698 
-3 693 692 698 
-3 693 698 699 
-3 694 693 699 
-3 694 699 700 
-3 695 694 700 
-3 695 700 701 
-3 696 695 701 
-3 696 701 702 
-3 697 602 604 
-3 697 604 703 
-3 698 697 703 
-3 698 703 704 
-3 699 698 704 
-3 699 704 705 
-3 700 699 705 
-3 700 705 706 
-3 701 700 706 
-3 701 706 707 
-3 702 701 707 
-3 702 707 708 
-3 703 604 606 
-3 703 606 709 
-3 704 703 709 
-3 704 709 710 
-3 705 704 710 
-3 705 710 711 
-3 706 705 711 
-3 706 711 712 
-3 707 706 712 
-3 707 712 713 
-3 708 707 713 
-3 708 713 714 
-3 709 606 608 
-3 709 608 715 
-3 710 709 715 
-3 710 715 716 
-3 711 710 716 
-3 711 716 717 
-3 712 711 717 
-3 712 717 718 
-3 713 712 718 
-3 713 718 719 
-3 714 713 719 
-3 714 719 720 
-3 715 608 610 
-3 715 610 721 
-3 716 715 721 
-3 716 721 722 
-3 717 716 722 
-3 717 722 723 
-3 718 717 723 
-3 718 723 724 
-3 719 718 724 
-3 719 724 725 
-3 720 719 725 
-3 720 725 726 
-3 721 610 612 
-3 721 612 727 
-3 722 721 727 
-3 722 727 728 
-3 723 722 728 
-3 723 728 729 
-3 724 723 729 
-3 724 729 730 
-3 725 724 730 
-3 725 730 731 
-3 726 725 731 
-3 726 731 732 
-3 727 612 614 
-3 727 614 733 
-3 728 727 733 
-3 728 733 734 
-3 729 728 734 
-3 729 734 735 
-3 730 729 735 
-3 730 735 736 
-3 731 730 736 
-3 731 736 737 
-3 732 731 737 
-3 732 737 738 
-3 733 614 616 
-3 733 616 739 
-3 734 733 739 
-3 734 739 740 
-3 735 734 740 
-3 735 740 741 
-3 736 735 741 
-3 736 741 742 
-3 737 736 742 
-3 737 742 743 
-3 738 737 743 
-3 738 743 744 
-3 739 616 618 
-3 739 618 745 
-3 740 739 745 
-3 740 745 746 
-3 741 740 746 
-3 741 746 747 
-3 742 741 747 
-3 742 747 748 
-3 743 742 748 
-3 743 748 749 
-3 744 743 749 
-3 744 749 750 
-3 745 618 620 
-3 745 620 751 
-3 746 745 751 
-3 746 751 752 
-3 747 746 752 
-3 747 752 753 
-3 748 747 753 
-3 748 753 754 
-3 749 748 754 
-3 749 754 755 
-3 750 749 755 
-3 750 755 756 
-3 751 620 622 
-3 751 622 757 
-3 752 751 757 
-3 752 757 758 
-3 753 752 758 
-3 753 758 759 
-3 754 753 759 
-3 754 759 760 
-3 755 754 760 
-3 755 760 761 
-3 756 755 761 
-3 756 761 762 
-3 757 622 624 
-3 757 624 763 
-3 758 757 763 
-3 758 763 764 
-3 759 758 764 
-3 759 764 765 
-3 760 759 765 
-3 760 765 766 
-3 761 760 766 
-3 761 766 767 
-3 762 761 767 
-3 762 767 768 
-3 763 624 577 
-3 763 577 625 
-3 764 763 625 
-3 764 625 627 
-3 765 764 627 
-3 765 627 629 
-3 766 765 629 
-3 766 629 631 
-3 767 766 631 
-3 767 631 633 
-3 768 767 633 
-3 768 633 635 
-3 769 770 771 
-3 769 771 772 
-3 773 769 772 
-3 773 772 774 
-3 775 773 774 
-3 775 774 776 
-3 777 775 776 
-3 777 776 778 
-3 779 777 778 
-3 779 778 780 
-3 781 779 780 
-3 781 780 782 
-3 772 771 783 
-3 772 783 784 
-3 774 772 784 
-3 774 784 785 
-3 776 774 785 
-3 776 785 786 
-3 778 776 786 
-3 778 786 787 
-3 780 778 787 
-3 780 787 788 
-3 782 780 788 
-3 782 788 789 
-3 784 783 790 
-3 784 790 791 
-3 785 784 791 
-3 785 791 792 
-3 786 785 792 
-3 786 792 793 
-3 787 786 793 
-3 787 793 794 
-3 788 787 794 
-3 788 794 795 
-3 789 788 795 
-3 789 795 796 
-3 791 790 797 
-3 791 797 798 
-3 792 791 798 
-3 792 798 799 
-3 793 792 799 
-3 793 799 800 
-3 794 793 800 
-3 794 800 801 
-3 795 794 801 
-3 795 801 802 
-3 796 795 802 
-3 796 802 803 
-3 798 797 804 
-3 798 804 805 
-3 799 798 805 
-3 799 805 806 
-3 800 799 806 
-3 800 806 807 
-3 801 800 807 
-3 801 807 808 
-3 802 801 808 
-3 802 808 809 
-3 803 802 809 
-3 803 809 810 
-3 805 804 811 
-3 805 811 812 
-3 806 805 812 
-3 806 812 813 
-3 807 806 813 
-3 807 813 814 
-3 808 807 814 
-3 808 814 815 
-3 809 808 815 
-3 809 815 816 
-3 810 809 816 
-3 810 816 817 
-3 812 811 818 
-3 812 818 819 
-3 813 812 819 
-3 813 819 820 
-3 814 813 820 
-3 814 820 821 
-3 815 814 821 
-3 815 821 822 
-3 816 815 822 
-3 816 822 823 
-3 817 816 823 
-3 817 823 824 
-3 819 818 825 
-3 819 825 826 
-3 820 819 826 
-3 820 826 827 
-3 821 820 827 
-3 821 827 828 
-3 822 821 828 
-3 822 828 829 
-3 823 822 829 
-3 823 829 830 
-3 824 823 830 
-3 824 830 831 
-3 826 825 832 
-3 826 832 833 
-3 827 826 833 
-3 827 833 834 
-3 828 827 834 
-3 828 834 835 
-3 829 828 835 
-3 829 835 836 
-3 830 829 836 
-3 830 836 837 
-3 831 830 837 
-3 831 837 838 
-3 833 832 839 
-3 833 839 840 
-3 834 833 840 
-3 834 840 841 
-3 835 834 841 
-3 835 841 842 
-3 836 835 842 
-3 836 842 843 
-3 837 836 843 
-3 837 843 844 
-3 838 837 844 
-3 838 844 845 
-3 840 839 846 
-3 840 846 847 
-3 841 840 847 
-3 841 847 848 
-3 842 841 848 
-3 842 848 849 
-3 843 842 849 
-3 843 849 850 
-3 844 843 850 
-3 844 850 851 
-3 845 844 851 
-3 845 851 852 
-3 847 846 770 
-3 847 770 769 
-3 848 847 769 
-3 848 769 773 
-3 849 848 773 
-3 849 773 775 
-3 850 849 775 
-3 850 775 777 
-3 851 850 777 
-3 851 777 779 
-3 852 851 779 
-3 852 779 781 
-3 853 781 782 
-3 853 782 854 
-3 855 853 854 
-3 855 854 856 
-3 857 855 856 
-3 857 856 858 
-3 859 857 858 
-3 859 858 860 
-3 861 859 860 
-3 861 860 862 
-3 245 861 862 
-3 245 862 863 
-3 854 782 789 
-3 854 789 864 
-3 856 854 864 
-3 856 864 865 
-3 858 856 865 
-3 858 865 866 
-3 860 858 866 
-3 860 866 867 
-3 862 860 867 
-3 862 867 868 
-3 863 862 868 
-3 863 868 869 
-3 864 789 796 
-3 864 796 870 
-3 865 864 870 
-3 865 870 871 
-3 866 865 871 
-3 866 871 872 
-3 867 866 872 
-3 867 872 873 
-3 868 867 873 
-3 868 873 874 
-3 869 868 874 
-3 869 874 875 
-3 870 796 803 
-3 870 803 876 
-3 871 870 876 
-3 871 876 877 
-3 872 871 877 
-3 872 877 878 
-3 873 872 878 
-3 873 878 879 
-3 874 873 879 
-3 874 879 880 
-3 875 874 880 
-3 875 880 881 
-3 876 803 810 
-3 876 810 882 
-3 877 876 882 
-3 877 882 883 
-3 878 877 883 
-3 878 883 884 
-3 879 878 884 
-3 879 884 885 
-3 880 879 885 
-3 880 885 886 
-3 881 880 886 
-3 881 886 887 
-3 882 810 817 
-3 882 817 888 
-3 883 882 888 
-3 883 888 889 
-3 884 883 889 
-3 884 889 890 
-3 885 884 890 
-3 885 890 891 
-3 886 885 891 
-3 886 891 892 
-3 887 886 892 
-3 887 892 893 
-3 888 817 824 
-3 888 824 894 
-3 889 888 894 
-3 889 894 895 
-3 890 889 895 
-3 890 895 896 
-3 891 890 896 
-3 891 896 897 
-3 892 891 897 
-3 892 897 898 
-3 893 892 898 
-3 893 898 899 
-3 894 824 831 
-3 894 831 900 
-3 895 894 900 
-3 895 900 901 
-3 896 895 901 
-3 896 901 902 
-3 897 896 902 
-3 897 902 903 
-3 898 897 903 
-3 898 903 904 
-3 899 898 904 
-3 899 904 905 
-3 900 831 838 
-3 900 838 906 
-3 901 900 906 
-3 901 906 907 
-3 902 901 907 
-3 902 907 908 
-3 903 902 908 
-3 903 908 909 
-3 904 903 909 
-3 904 909 910 
-3 905 904 910 
-3 905 910 911 
-3 906 838 845 
-3 906 845 912 
-3 907 906 912 
-3 907 912 913 
-3 908 907 913 
-3 908 913 914 
-3 909 908 914 
-3 909 914 915 
-3 910 909 915 
-3 910 915 916 
-3 911 910 916 
-3 911 916 917 
-3 912 845 852 
-3 912 852 918 
-3 913 912 918 
-3 913 918 919 
-3 914 913 919 
-3 914 919 920 
-3 915 914 920 
-3 915 920 921 
-3 916 915 921 
-3 916 921 922 
-3 917 916 922 
-3 917 922 923 
-3 918 852 781 
-3 918 781 853 
-3 919 918 853 
-3 919 853 855 
-3 920 919 855 
-3 920 855 857 
-3 921 920 857 
-3 921 857 859 
-3 922 921 859 
-3 922 859 861 
-3 923 922 861 
-3 923 861 245 
-3 924 925 926 
-3 924 926 927 
-3 928 924 927 
-3 928 927 929 
-3 930 928 929 
-3 930 929 931 
-3 932 930 931 
-3 932 931 933 
-3 934 932 933 
-3 934 933 935 
-3 936 934 935 
-3 936 935 937 
-3 927 926 938 
-3 927 938 939 
-3 929 927 939 
-3 929 939 940 
-3 931 929 940 
-3 931 940 941 
-3 933 931 941 
-3 933 941 942 
-3 935 933 942 
-3 935 942 943 
-3 937 935 943 
-3 937 943 944 
-3 939 938 945 
-3 939 945 946 
-3 940 939 946 
-3 940 946 947 
-3 941 940 947 
-3 941 947 948 
-3 942 941 948 
-3 942 948 949 
-3 943 942 949 
-3 943 949 950 
-3 944 943 950 
-3 944 950 951 
-3 946 945 952 
-3 946 952 953 
-3 947 946 953 
-3 947 953 954 
-3 948 947 954 
-3 948 954 955 
-3 949 948 955 
-3 949 955 956 
-3 950 949 956 
-3 950 956 957 
-3 951 950 957 
-3 951 957 958 
-3 953 952 959 
-3 953 959 960 
-3 954 953 960 
-3 954 960 961 
-3 955 954 961 
-3 955 961 962 
-3 956 955 962 
-3 956 962 963 
-3 957 956 963 
-3 957 963 964 
-3 958 957 964 
-3 958 964 965 
-3 960 959 966 
-3 960 966 967 
-3 961 960 967 
-3 961 967 968 
-3 962 961 968 
-3 962 968 969 
-3 963 962 969 
-3 963 969 970 
-3 964 963 970 
-3 964 970 971 
-3 965 964 971 
-3 965 971 972 
-3 967 966 973 
-3 967 973 974 
-3 968 967 974 
-3 968 974 975 
-3 969 968 975 
-3 969 975 976 
-3 970 969 976 
-3 970 976 977 
-3 971 970 977 
-3 971 977 978 
-3 972 971 978 
-3 972 978 979 
-3 974 973 980 
-3 974 980 981 
-3 975 974 981 
-3 975 981 982 
-3 976 975 982 
-3 976 982 983 
-3 977 976 983 
-3 977 983 984 
-3 978 977 984 
-3 978 984 985 
-3 979 978 985 
-3 979 985 986 
-3 981 980 987 
-3 981 987 988 
-3 982 981 988 
-3 982 988 989 
-3 983 982 989 
-3 983 989 990 
-3 984 983 990 
-3 984 990 991 
-3 985 984 991 
-3 985 991 992 
-3 986 985 992 
-3 986 992 993 
-3 988 987 994 
-3 988 994 995 
-3 989 988 995 
-3 989 995 996 
-3 990 989 996 
-3 990 996 997 
-3 991 990 997 
-3 991 997 998 
-3 992 991 998 
-3 992 998 999 
-3 993 992 999 
-3 993 999 1000 
-3 995 994 1001 
-3 995 1001 1002 
-3 996 995 1002 
-3 996 1002 1003 
-3 997 996 1003 
-3 997 1003 1004 
-3 998 997 1004 
-3 998 1004 1005 
-3 999 998 1005 
-3 999 1005 1006 
-3 1000 999 1006 
-3 1000 1006 1007 
-3 1002 1001 925 
-3 1002 925 924 
-3 1003 1002 924 
-3 1003 924 928 
-3 1004 1003 928 
-3 1004 928 930 
-3 1005 1004 930 
-3 1005 930 932 
-3 1006 1005 932 
-3 1006 932 934 
-3 1007 1006 934 
-3 1007 934 936 
-3 1008 936 937 
-3 1008 937 1009 
-3 1010 1008 1009 
-3 1010 1009 1011 
-3 1012 1010 1011 
-3 1012 1011 1013 
-3 1014 1012 1013 
-3 1014 1013 1015 
-3 1016 1014 1015 
-3 1016 1015 1017 
-3 1018 1016 1017 
-3 1018 1017 1019 
-3 1009 937 944 
-3 1009 944 1020 
-3 1011 1009 1020 
-3 1011 1020 1021 
-3 1013 1011 1021 
-3 1013 1021 1022 
-3 1015 1013 1022 
-3 1015 1022 1023 
-3 1017 1015 1023 
-3 1017 1023 1024 
-3 1019 1017 1024 
-3 1019 1024 1025 
-3 1020 944 951 
-3 1020 951 1026 
-3 1021 1020 1026 
-3 1021 1026 1027 
-3 1022 1021 1027 
-3 1022 1027 1028 
-3 1023 1022 1028 
-3 1023 1028 1029 
-3 1024 1023 1029 
-3 1024 1029 1030 
-3 1025 1024 1030 
-3 1025 1030 1031 
-3 1026 951 958 
-3 1026 958 1032 
-3 1027 1026 1032 
-3 1027 1032 1033 
-3 1028 1027 1033 
-3 1028 1033 1034 
-3 1029 1028 1034 
-3 1029 1034 1035 
-3 1030 1029 1035 
-3 1030 1035 1036 
-3 1031 1030 1036 
-3 1031 1036 1037 
-3 1032 958 965 
-3 1032 965 1038 
-3 1033 1032 1038 
-3 1033 1038 1039 
-3 1034 1033 1039 
-3 1034 1039 1040 
-3 1035 1034 1040 
-3 1035 1040 1041 
-3 1036 1035 1041 
-3 1036 1041 1042 
-3 1037 1036 1042 
-3 1037 1042 1043 
-3 1038 965 972 
-3 1038 972 1044 
-3 1039 1038 1044 
-3 1039 1044 1045 
-3 1040 1039 1045 
-3 1040 1045 1046 
-3 1041 1040 1046 
-3 1041 1046 1047 
-3 1042 1041 1047 
-3 1042 1047 1048 
-3 1043 1042 1048 
-3 1043 1048 1049 
-3 1044 972 979 
-3 1044 979 1050 
-3 1045 1044 1050 
-3 1045 1050 1051 
-3 1046 1045 1051 
-3 1046 1051 1052 
-3 1047 1046 1052 
-3 1047 1052 1053 
-3 1048 1047 1053 
-3 1048 1053 1054 
-3 1049 1048 1054 
-3 1049 1054 1055 
-3 1050 979 986 
-3 1050 986 1056 
-3 1051 1050 1056 
-3 1051 1056 1057 
-3 1052 1051 1057 
-3 1052 1057 1058 
-3 1053 1052 1058 
-3 1053 1058 1059 
-3 1054 1053 1059 
-3 1054 1059 1060 
-3 1055 1054 1060 
-3 1055 1060 1061 
-3 1056 986 993 
-3 1056 993 1062 
-3 1057 1056 1062 
-3 1057 1062 1063 
-3 1058 1057 1063 
-3 1058 1063 1064 
-3 1059 1058 1064 
-3 1059 1064 1065 
-3 1060 1059 1065 
-3 1060 1065 1066 
-3 1061 1060 1066 
-3 1061 1066 1067 
-3 1062 993 1000 
-3 1062 1000 1068 
-3 1063 1062 1068 
-3 1063 1068 1069 
-3 1064 1063 1069 
-3 1064 1069 1070 
-3 1065 1064 1070 
-3 1065 1070 1071 
-3 1066 1065 1071 
-3 1066 1071 1072 
-3 1067 1066 1072 
-3 1067 1072 1073 
-3 1068 1000 1007 
-3 1068 1007 1074 
-3 1069 1068 1074 
-3 1069 1074 1075 
-3 1070 1069 1075 
-3 1070 1075 1076 
-3 1071 1070 1076 
-3 1071 1076 1077 
-3 1072 1071 1077 
-3 1072 1077 1078 
-3 1073 1072 1078 
-3 1073 1078 1079 
-3 1074 1007 936 
-3 1074 936 1008 
-3 1075 1074 1008 
-3 1075 1008 1010 
-3 1076 1075 1010 
-3 1076 1010 1012 
-3 1077 1076 1012 
-3 1077 1012 1014 
-3 1078 1077 1014 
-3 1078 1014 1016 
-3 1079 1078 1016 
-3 1079 1016 1018 
-3 1080 1081 1082 
-3 1083 1080 1082 
-3 1083 1082 1084 
-3 1085 1083 1084 
-3 1085 1084 1086 
-3 1087 1085 1086 
-3 1087 1086 1088 
-3 578 1087 1088 
-3 578 1088 579 
-3 1082 1081 1089 
-3 1084 1082 1089 
-3 1084 1089 1090 
-3 1086 1084 1090 
-3 1086 1090 1091 
-3 1088 1086 1091 
-3 1088 1091 1092 
-3 579 1088 1092 
-3 579 1092 581 
-3 1089 1081 1093 
-3 1090 1089 1093 
-3 1090 1093 1094 
-3 1091 1090 1094 
-3 1091 1094 1095 
-3 1092 1091 1095 
-3 1092 1095 1096 
-3 581 1092 1096 
-3 581 1096 583 
-3 1093 1081 1097 
-3 1094 1093 1097 
-3 1094 1097 1098 
-3 1095 1094 1098 
-3 1095 1098 1099 
-3 1096 1095 1099 
-3 1096 1099 1100 
-3 583 1096 1100 
-3 583 1100 585 
-3 1097 1081 1101 
-3 1098 1097 1101 
-3 1098 1101 1102 
-3 1099 1098 1102 
-3 1099 1102 1103 
-3 1100 1099 1103 
-3 1100 1103 1104 
-3 585 1100 1104 
-3 585 1104 587 
-3 1101 1081 1105 
-3 1102 1101 1105 
-3 1102 1105 1106 
-3 1103 1102 1106 
-3 1103 1106 1107 
-3 1104 1103 1107 
-3 1104 1107 1108 
-3 587 1104 1108 
-3 587 1108 589 
-3 1105 1081 1109 
-3 1106 1105 1109 
-3 1106 1109 1110 
-3 1107 1106 1110 
-3 1107 1110 1111 
-3 1108 1107 1111 
-3 1108 1111 1112 
-3 589 1108 1112 
-3 589 1112 591 
-3 1109 1081 1113 
-3 1110 1109 1113 
-3 1110 1113 1114 
-3 1111 1110 1114 
-3 1111 1114 1115 
-3 1112 1111 1115 
-3 1112 1115 1116 
-3 591 1112 1116 
-3 591 1116 593 
-3 1113 1081 1117 
-3 1114 1113 1117 
-3 1114 1117 1118 
-3 1115 1114 1118 
-3 1115 1118 1119 
-3 1116 1115 1119 
-3 1116 1119 1120 
-3 593 1116 1120 
-3 593 1120 595 
-3 1117 1081 1121 
-3 1118 1117 1121 
-3 1118 1121 1122 
-3 1119 1118 1122 
-3 1119 1122 1123 
-3 1120 1119 1123 
-3 1120 1123 1124 
-3 595 1120 1124 
-3 595 1124 597 
-3 1121 1081 1125 
-3 1122 1121 1125 
-3 1122 1125 1126 
-3 1123 1122 1126 
-3 1123 1126 1127 
-3 1124 1123 1127 
-3 1124 1127 1128 
-3 597 1124 1128 
-3 597 1128 599 
-3 1125 1081 1129 
-3 1126 1125 1129 
-3 1126 1129 1130 
-3 1127 1126 1130 
-3 1127 1130 1131 
-3 1128 1127 1131 
-3 1128 1131 1132 
-3 599 1128 1132 
-3 599 1132 601 
-3 1129 1081 1133 
-3 1130 1129 1133 
-3 1130 1133 1134 
-3 1131 1130 1134 
-3 1131 1134 1135 
-3 1132 1131 1135 
-3 1132 1135 1136 
-3 601 1132 1136 
-3 601 1136 603 
-3 1133 1081 1137 
-3 1134 1133 1137 
-3 1134 1137 1138 
-3 1135 1134 1138 
-3 1135 1138 1139 
-3 1136 1135 1139 
-3 1136 1139 1140 
-3 603 1136 1140 
-3 603 1140 605 
-3 1137 1081 1141 
-3 1138 1137 1141 
-3 1138 1141 1142 
-3 1139 1138 1142 
-3 1139 1142 1143 
-3 1140 1139 1143 
-3 1140 1143 1144 
-3 605 1140 1144 
-3 605 1144 607 
-3 1141 1081 1145 
-3 1142 1141 1145 
-3 1142 1145 1146 
-3 1143 1142 1146 
-3 1143 1146 1147 
-3 1144 1143 1147 
-3 1144 1147 1148 
-3 607 1144 1148 
-3 607 1148 609 
-3 1145 1081 1149 
-3 1146 1145 1149 
-3 1146 1149 1150 
-3 1147 1146 1150 
-3 1147 1150 1151 
-3 1148 1147 1151 
-3 1148 1151 1152 
-3 609 1148 1152 
-3 609 1152 611 
-3 1149 1081 1153 
-3 1150 1149 1153 
-3 1150 1153 1154 
-3 1151 1150 1154 
-3 1151 1154 1155 
-3 1152 1151 1155 
-3 1152 1155 1156 
-3 611 1152 1156 
-3 611 1156 613 
-3 1153 1081 1157 
-3 1154 1153 1157 
-3 1154 1157 1158 
-3 1155 1154 1158 
-3 1155 1158 1159 
-3 1156 1155 1159 
-3 1156 1159 1160 
-3 613 1156 1160 
-3 613 1160 615 
-3 1157 1081 1161 
-3 1158 1157 1161 
-3 1158 1161 1162 
-3 1159 1158 1162 
-3 1159 1162 1163 
-3 1160 1159 1163 
-3 1160 1163 1164 
-3 615 1160 1164 
-3 615 1164 617 
-3 1161 1081 1165 
-3 1162 1161 1165 
-3 1162 1165 1166 
-3 1163 1162 1166 
-3 1163 1166 1167 
-3 1164 1163 1167 
-3 1164 1167 1168 
-3 617 1164 1168 
-3 617 1168 619 
-3 1165 1081 1169 
-3 1166 1165 1169 
-3 1166 1169 1170 
-3 1167 1166 1170 
-3 1167 1170 1171 
-3 1168 1167 1171 
-3 1168 1171 1172 
-3 619 1168 1172 
-3 619 1172 621 
-3 1169 1081 1173 
-3 1170 1169 1173 
-3 1170 1173 1174 
-3 1171 1170 1174 
-3 1171 1174 1175 
-3 1172 1171 1175 
-3 1172 1175 1176 
-3 621 1172 1176 
-3 621 1176 623 
-3 1173 1081 1080 
-3 1174 1173 1080 
-3 1174 1080 1083 
-3 1175 1174 1083 
-3 1175 1083 1085 
-3 1176 1175 1085 
-3 1176 1085 1087 
-3 623 1176 1087 
-3 623 1087 578 
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/setup.cfg b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/setup.cfg
deleted file mode 100644
index 3a3e96841329437e52a596b572806c9ad4344947..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/setup.cfg
+++ /dev/null
@@ -1,4 +0,0 @@
-[develop]
-script-dir=$base/lib/pcd_demo
-[install]
-install-scripts=$base/lib/pcd_demo
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/setup.py b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/setup.py
deleted file mode 100644
index ed51ea1caf67e084ee817398b30b5b94ca9c15e2..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/setup.py
+++ /dev/null
@@ -1,37 +0,0 @@
-from setuptools import setup
-
-import os
-from glob import glob
-
-package_name = 'pcd_demo'
-
-setup(
-    name=package_name,
-    version='0.0.1',
-    packages=[package_name],
-    data_files=[
-        ('share/ament_index/resource_index/packages',
-            ['resource/' + package_name]),
-        ('share/' + package_name, ['package.xml']),
-        # During installation, we need to copy the launch files
-        (os.path.join('share', package_name, "launch"), glob('launch/*.launch.py')),
-        # Same with the RViz configuration file.
-        (os.path.join('share', package_name, "config"), glob('config/*')),
-        # And the ply files.
-        (os.path.join('share', package_name, "resource"), glob('resource/*.ply')),
-    ],
-    install_requires=['setuptools'],
-    zip_safe=True,
-    maintainer='Sebastian Grans',
-    maintainer_email='sebastian.grans@ntno.com',
-    description='Demo package on how to visualize a point cloud using RViz',
-    license='MIT License',
-    tests_require=['pytest'],
-    entry_points={
-        'console_scripts': [
-            'pcd_publisher_node = pcd_demo.pcd_publisher.pcd_publisher_node:main',
-            'pcd_subscriber_node = pcd_demo.pcd_subscriber.pcd_subscriber_node:main',
-            'ser_test_node = pcd_demo.ser_test.ser_test:main',
-        ],
-    },
-)
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/test/test_copyright.py b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/test/test_copyright.py
deleted file mode 100644
index cc8ff03f79abb8eb061827a24f2a331e052c5c37..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/test/test_copyright.py
+++ /dev/null
@@ -1,23 +0,0 @@
-# Copyright 2015 Open Source Robotics Foundation, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-#     http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-from ament_copyright.main import main
-import pytest
-
-
-@pytest.mark.copyright
-@pytest.mark.linter
-def test_copyright():
-    rc = main(argv=['.', 'test'])
-    assert rc == 0, 'Found errors'
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/test/test_flake8.py b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/test/test_flake8.py
deleted file mode 100644
index eff829969534949bd9d5512146a7b0029b4cec84..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/test/test_flake8.py
+++ /dev/null
@@ -1,23 +0,0 @@
-# Copyright 2017 Open Source Robotics Foundation, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-#     http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-from ament_flake8.main import main
-import pytest
-
-
-@pytest.mark.flake8
-@pytest.mark.linter
-def test_flake8():
-    rc = main(argv=[])
-    assert rc == 0, 'Found errors'
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/test/test_pep257.py b/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/test/test_pep257.py
deleted file mode 100644
index b234a3840f4c5bd38f043638c8622b8f240e1185..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/test/test_pep257.py
+++ /dev/null
@@ -1,23 +0,0 @@
-# Copyright 2015 Open Source Robotics Foundation, Inc.
-#
-# Licensed under the Apache License, Version 2.0 (the "License");
-# you may not use this file except in compliance with the License.
-# You may obtain a copy of the License at
-#
-#     http://www.apache.org/licenses/LICENSE-2.0
-#
-# Unless required by applicable law or agreed to in writing, software
-# distributed under the License is distributed on an "AS IS" BASIS,
-# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-# See the License for the specific language governing permissions and
-# limitations under the License.
-
-from ament_pep257.main import main
-import pytest
-
-
-@pytest.mark.linter
-@pytest.mark.pep257
-def test_pep257():
-    rc = main(argv=['.', 'test'])
-    assert rc == 0, 'Found code style errors / warnings'
diff --git a/workspaces/rob-sensor_ws/src/Universal_Robots_ROS2_Description b/workspaces/rob-sensor_ws/src/Universal_Robots_ROS2_Description
deleted file mode 160000
index 8a8808325a038f3cd4f452fa4eabfd4974e73067..0000000000000000000000000000000000000000
--- a/workspaces/rob-sensor_ws/src/Universal_Robots_ROS2_Description
+++ /dev/null
@@ -1 +0,0 @@
-Subproject commit 8a8808325a038f3cd4f452fa4eabfd4974e73067
diff --git a/workspaces/rob-sensor_ws/src/serial_to_pcl/package.xml b/workspaces/rob-sensor_ws/src/serial_to_pcl/package.xml
new file mode 100644
index 0000000000000000000000000000000000000000..4abfc908eca66846628362c1c2e38b98ac8d4998
--- /dev/null
+++ b/workspaces/rob-sensor_ws/src/serial_to_pcl/package.xml
@@ -0,0 +1,24 @@
+<?xml version="1.0"?>
+<package format="2">
+    <name>serial_to_pcl</name>
+    <version>0.0.1</version>
+    <description>ROS 2 package for serial communication testing</description>
+
+    <maintainer email="rene.ebeling@alumni.fh-aachen.de">Rene Ebeling</maintainer>
+    <license>Apache-2.0</license>
+
+    <buildtool_depend>ament_python</buildtool_depend>
+
+    <exec_depend>rclpy</exec_depend>
+    <exec_depend>std_msgs</exec_depend>
+    <exec_depend>sensor_msgs</exec_depend>
+    <exec_depend>numpy</exec_depend>
+    <exec_depend>pyserial</exec_depend>
+
+    <test_depend>ament_lint_auto</test_depend>
+    <test_depend>ament_lint_common</test_depend>
+
+    <export>
+        <build_type>ament_python</build_type>
+    </export>
+</package>
\ No newline at end of file
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_publisher/__init__.py b/workspaces/rob-sensor_ws/src/serial_to_pcl/resource/serial_to_pcl
similarity index 100%
rename from workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_publisher/__init__.py
rename to workspaces/rob-sensor_ws/src/serial_to_pcl/resource/serial_to_pcl
diff --git a/workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_subscriber/__init__.py b/workspaces/rob-sensor_ws/src/serial_to_pcl/serial_to_pcl/__init__.py
similarity index 100%
rename from workspaces/rob-sensor_ws/src/ROS2-Point-Cloud-Demo/pcd_demo/pcd_subscriber/__init__.py
rename to workspaces/rob-sensor_ws/src/serial_to_pcl/serial_to_pcl/__init__.py
diff --git a/workspaces/COLCON_WS/src/ser_test/ser_test/ser_test_node.py b/workspaces/rob-sensor_ws/src/serial_to_pcl/serial_to_pcl/serial_to_pcl_node.py
similarity index 100%
rename from workspaces/COLCON_WS/src/ser_test/ser_test/ser_test_node.py
rename to workspaces/rob-sensor_ws/src/serial_to_pcl/serial_to_pcl/serial_to_pcl_node.py
diff --git a/workspaces/rob-sensor_ws/src/serial_to_pcl/setup.py b/workspaces/rob-sensor_ws/src/serial_to_pcl/setup.py
new file mode 100755
index 0000000000000000000000000000000000000000..9a161fc9dd48fddb679726900a99154492159db2
--- /dev/null
+++ b/workspaces/rob-sensor_ws/src/serial_to_pcl/setup.py
@@ -0,0 +1,25 @@
+from setuptools import setup
+
+package_name = 'serial_to_pcl'
+
+setup(
+    name=package_name,
+    version='0.0.1',
+    packages=[package_name],
+    data_files=[
+        ('share/ament_index/resource_index/packages',
+         ['resource/' + package_name]),
+        ('share/' + package_name, ['package.xml']),
+    ],
+    install_requires=['setuptools', 'rclpy', 'pyserial', 'numpy'],
+    zip_safe=True,
+    author='Rene Ebeling',
+    author_email='rene.ebeling@alumni.fh-aachen.de',
+    description='ROS 2 package for serial communication testing',
+    license='Apache-2.0',
+    entry_points={
+        'console_scripts': [
+            'serial_to_pcl_node = serial_to_pcl.serial_to_pcl_node:main'
+        ],
+    },
+)