diff --git a/ros2/build/.built_by b/ros2/build/.built_by
deleted file mode 100644
index 06e74acb63e6917bd1f0f8853213d49f0c5978e4..0000000000000000000000000000000000000000
--- a/ros2/build/.built_by
+++ /dev/null
@@ -1 +0,0 @@
-colcon
diff --git a/ros2/build/COLCON_IGNORE b/ros2/build/COLCON_IGNORE
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/build/robobin/build/lib/robobin/__init__.py b/ros2/build/robobin/build/lib/robobin/__init__.py
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/build/robobin/build/lib/robobin/api_node.py b/ros2/build/robobin/build/lib/robobin/api_node.py
deleted file mode 100644
index d83622c7d0d85e12c642f1fad0dfe9b411b6dd60..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/build/lib/robobin/api_node.py
+++ /dev/null
@@ -1,106 +0,0 @@
-
-# robobin/api_node.py
-from .helpers.message_handler import MessageHandler
-from .helpers.connection_manager import ConnectionManager
-
-from geometry_msgs.msg import Twist
-from geometry_msgs.msg import Point
-from std_msgs.msg import String
-import rclpy
-from rclpy.node import Node
-
-class ApiNode(Node):
-    def __init__(self):
-        super().__init__('api_node')
-        self.get_logger().info("ApiNode has been started.")
-
-        self.publisher_topics = {
-            "cmd_vel": self.create_publisher(Twist, '/cmd_vel', 10),
-            "nav_send": self.create_publisher(Twist, '/nav_send', 10), 
-            "nav_command": self.create_publisher(String, '/nav_command', 10),
-        }
-        self.location_subscriber = self.create_subscription(
-            Point,  # Message type
-            '/tag1_location',  # Topic
-            self.handle_location_update,  # Callback
-            10  # QoS depth
-        )
-        self.mode = "Manual"
-        self.called_locations = [] # List of  pairs of ip address and location
-        self.message_handler = MessageHandler(self)
-        self.connection_manager = ConnectionManager(self)
-
-        self.connection_manager.start()
-        self.get_logger().info("Connection manager started.")
-    def handle_client_connection(self, client_socket):
-        """Handles incoming TCP client connections."""
-        try:
-            while True:
-                data = client_socket.recv(1024).decode()
-                if not data:
-                    break
-                self.get_logger().info(f"Received data: {data}")
-                test = data.split(" ", 1)
-                self.get_logger().info(f"Received command: {test[0]}")
-                result = self.message_handler.handle_message(client_socket, data)
-        
-                # Check if the result is not None
-                if result is not None:
-                    topic, message = result  # Safely unpack after checking
-                    if topic is not None:
-                        self.get_logger().info(f"Publishing to topic: {topic}")
-                        self.publish_to_topic(topic, message)
-        finally:
-            client_socket.close()
-            self.get_logger().info("Client disconnected.")
-    def publish_to_topic(self, topic, message):
-        self.get_logger().info(f"Publishing to topic: {topic}")
-        """Publishes the message to the specified topic."""
-        if topic in self.publisher_topics:
-            publisher = self.publisher_topics[topic]
-
-            # Check if the topic is 'cmd_vel' and format the message as a Twist message
-            if topic == "cmd_vel" and isinstance(message, tuple):
-                linear_x, angular_z = message
-                twist_msg = Twist()
-                twist_msg.linear.x = linear_x
-                twist_msg.linear.y = 0.0
-                twist_msg.linear.z = 0.0
-                twist_msg.angular.x = 0.0
-                twist_msg.angular.y = 0.0
-                twist_msg.angular.z = angular_z
-
-                publisher.publish(twist_msg)
-                self.get_logger().info(f"Published to {topic}: linear_x={linear_x}, angular_z={angular_z}")
-            elif topic == "nav_command" and isinstance(message, str):
-                self.get_logger().info(f"Published to {topic}: {message}")
-                publisher.publish(String(data=message))
-            else:
-                self.get_logger().warning(f"Unhandled message type for topic: {topic}")
-        else:
-            self.get_logger().warning(f"Unknown topic: {topic}")
-    def handle_location_update(self, msg):
-        self.get_logger().info("Received updated location.")
-        self.get_logger().info(f"Received updated location: x={msg.x:.2f}, y={msg.y:.2f}")
-        """Callback for the /tag1_location topic."""
-        x = msg.x
-        y = msg.y
-        self.connection_manager.set_location(x, y)
-        self.get_logger().info(f"Received updated location: x={x:.2f}, y={y:.2f}")
-    def shutdown(self):
-        """Stops the connection manager."""
-        self.connection_manager.stop()
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = ApiNode()
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        node.shutdown()
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/build/robobin/build/lib/robobin/control_feedback.py b/ros2/build/robobin/build/lib/robobin/control_feedback.py
deleted file mode 100644
index 78a1edb74b03fbdf991c9e38c1b8980ee52b3945..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/build/lib/robobin/control_feedback.py
+++ /dev/null
@@ -1,320 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Twist
-from std_msgs.msg import Int64, Float64
-from gpiozero import PWMOutputDevice, DigitalOutputDevice
-import time
-from rclpy.clock import Clock
-from rclpy.time import Time
-import bisect
-
-
-
-# Example of how you could implement a simple PID controller
-class PIDController:
-    def __init__(self, kp, ki, kd):
-        self.kp = kp
-        self.ki = ki
-        self.kd = kd
-        self.prev_error = 0
-        self.integral = 0
-
-    def reset(self):
-        self.prev_error = 0
-        self.integral = 0
-
-    def calculate(self, error, dt):
-        self.integral += error * dt
-        derivative = (error - self.prev_error) / dt 
-        output = self.kp * error + self.ki * self.integral + self.kd * derivative
-        self.prev_error = error
-        return output
-
-
-
-
-class MotorControlNode(Node):
-    def __init__(self):
-        super().__init__('control_feedback_node')
-
-        # Initialize encoder values
-        self.encoder_left_steps = 0
-        self.encoder_right_steps = 0
-
-        # Desired speeds from cmd_vel
-        self.desired_linear_speed = 0.0
-        self.desired_angular_speed = 0.0
-
-        self.prev_left_steps = 0
-        self.prev_right_steps = 0
-
-        self.left_pwm = 0
-        self.right_pwm = 0
-
-        self.prev_desired_speed = 0.0
-
-
-        #Time
-        self.prev_time = time.time()
-        #self.prev_time = self.get_clock().now
-
-        
-        # Robot parameters
-        self.wheel_base = 0.40  
-        self.encoder_steps_per_rotation = 310  
-        self.wheel_radius = 0.075 
-
-        # Initialize the motors
-        self.motor = Motor(self,14,15,18, 17, 22, 27)
-
-        # PID controllers
-        self.pid_left_forward = PIDController(kp=0.5, ki=0.0, kd=0.001)
-        self.pid_right_forward = PIDController(kp=0.525, ki=0.0, kd=0.001)
-
-        self.pid_left_backward = PIDController(kp=0.525, ki=0.0, kd=0.001)
-        self.pid_right_backward = PIDController(kp=0.5, ki=0.0, kd=0.001)
-
-
-
-
-        # Subscribe to cmd_vel topic
-        self.subscription = self.create_subscription(
-            Twist,
-            '/cmd_vel',
-            self.cmd_vel_callback,
-            10
-        )
-
-        # Subscribe to encoder data
-        self.left_encoder_sub = self.create_subscription(
-            Int64,
-            'left_wheel_steps',
-            self.left_encoder_callback,
-            10
-        )
-        self.right_encoder_sub = self.create_subscription(
-            Int64,
-            'right_wheel_steps',
-            self.right_encoder_callback,
-            10
-        )
-
-        self.left_actual_speed_pub = self.create_publisher(Float64, 'left_actual_wheel_speed', 10)
-        self.right_actual_speed_pub = self.create_publisher(Float64, 'right_actual_wheel_speed', 10)
-        self.desired_speed_pub = self.create_publisher(Float64, 'desired_wheel_speed', 10)
-
-        # Timer to update motor speeds
-        self.control_timer = self.create_timer(0.1, self.control_loop)
-
-        self.get_logger().info('Motor control node with encoder feedback has been started.')
-
-    def cmd_vel_callback(self, msg):
-        # Store desired speeds
-        self.desired_linear_speed = msg.linear.x  # Forward/backward speed
-        self.desired_angular_speed = msg.angular.z  # Turning rate
-
-        # if (self.desired_linear_speed >= 0 and self.prev_desired_speed < 0) or (self.desired_linear_speed < 0 and self.prev_desired_speed >= 0):
-
-        #     self.pid_left_forward.reset()
-        #     self.pid_right_forward.reset()
-        #     self.pid_left_backward.reset()
-        #     self.pid_right_backward.reset()
-
-
-
-        
-
-        self.prev_desired_speed = self.desired_linear_speed
-
-    def left_encoder_callback(self, msg):
-        self.encoder_left_steps = msg.data
-
-    def right_encoder_callback(self, msg):
-        self.encoder_right_steps = msg.data
-
-    
-    def control_loop(self):
-
-        if self.desired_linear_speed >= 0:
-            # Forward motion
-            left_pid = self.pid_left_forward
-            right_pid = self.pid_right_forward
-        else:
-            # Backward motion
-            left_pid = self.pid_left_backward
-            right_pid = self.pid_right_backward
-
-        if (self.desired_linear_speed == 0) and (self.desired_angular_speed == 0):
-            self.stop_motors()
-            self.pid_left_forward.reset()
-            self.pid_right_forward.reset()
-            self.pid_left_backward.reset()
-            self.pid_right_backward.reset()
-            self.left_pwm =0
-            self.right_pwm =0
-            return
-
-
-
-
-        #Calculate the actual speed
-        #-------------------------------
-        # Calculate elapsed time
-        current_time = time.time()
-        #dt = current_time - self.prev_time
-        dt = max(current_time - self.prev_time, 0.01)  # Prevent dt from being too small
-        #dt = max(current_time - self.prev_time, 1e-6)  # Avoid zero or too small dt
-        if dt == 0:
-            return
-        self.prev_time = current_time
-
-        # self.prev_time = self.get_clock().now()
-        # current_time = self.get_clock().now()
-        # dt = (current_time - self.prev_time).to_sec()
-        # if dt <= 0.0:
-        #     return
-        # self.prev_time = current_time
-
-        #Actual Speed calculation
-        #------------------------------------
-        # Calculate change in encoder steps
-        delta_left_steps = self.encoder_left_steps - self.prev_left_steps
-        delta_right_steps = self.encoder_right_steps - self.prev_right_steps
-
-        self.prev_left_steps = self.encoder_left_steps
-        self.prev_right_steps = self.encoder_right_steps
-
-        # Calculate rotational speeds (RPS)
-        left_rps = delta_left_steps / (self.encoder_steps_per_rotation * dt)
-        right_rps = delta_right_steps / (self.encoder_steps_per_rotation * dt)
-
-        # Convert to linear speed (m/s)
-        left_speed_actual = left_rps * 2 * 3.14159 * self.wheel_radius
-        right_speed_actual = right_rps * 2 * 3.14159 * self.wheel_radius
-
-
-
-        #Desired Speed calculation
-        #------------------------------------
-        # Desired speeds for left and right wheels
-        left_speed_desired = self.desired_linear_speed - (self.desired_angular_speed * self.wheel_base / 2.0)
-        right_speed_desired = self.desired_linear_speed + (self.desired_angular_speed * self.wheel_base / 2.0)
-
-
-
-        # Speed Errors calculation
-        #------------------------------------
-        left_error = left_speed_desired - left_speed_actual
-        right_error = right_speed_desired - right_speed_actual
-
- 
-
-        # Use PID controllers for left and right wheels
-        left_pwm_error = left_pid.calculate(left_error, dt)
-        right_pwm_error = right_pid.calculate(right_error, dt)
-
-        self.left_pwm +=   left_pwm_error
-        self.right_pwm +=  right_pwm_error
-
-
-
-        # Ensure PWM values are within [-1, 1]
-        left_pwm = max(-1, min(1, self.left_pwm))
-        right_pwm = max(-1, min(1, self.right_pwm))
-
-        # Apply PWM values to motors
-        self.motor.set_pwm(left_pwm, right_pwm)
-
-        
-
-
-        # Publish actual speeds
-        left_actual_speed_msg = Float64()
-        left_actual_speed_msg.data = left_speed_actual
-        self.left_actual_speed_pub.publish(left_actual_speed_msg)
-
-        right_actual_speed_msg = Float64()
-        right_actual_speed_msg.data = right_speed_actual
-        self.right_actual_speed_pub.publish(right_actual_speed_msg)
-
-        desired_speed_msg = Float64()
-        desired_speed_msg.data = right_speed_desired
-        self.desired_speed_pub.publish(desired_speed_msg)
-
-
-        # Debugging info
-        # self.get_logger().info(f'Left PWM IN: {self.left_pwm:.2f}, Right PWM IN: {right_pwm:.2f}')
-        # self.get_logger().info(f'Left Speed Actual: {left_speed_actual:.2f}, Right Speed Actual: {right_speed_actual:.2f}')
-        # self.get_logger().info(f'Left Error: {left_error:.2f}, Right Error: {left_pwm_error:.2f}')
-        # self.get_logger().info(f'Left_speed_desired: {left_speed_desired:.2f}, Right_speed_desired: {right_speed_desired:.2f}')
-        # self.get_logger().info('-----------------------------------------------------------------')
-
-
-    def stop_motors(self):
-        self.motor.stop()
-        # self.get_logger().info('Motors have been stopped.')
-
-class Motor:
-    def __init__(self,node, EnaA, In1A, In2A, EnaB, In1B, In2B):
-
-        self.node = node
-        # Left motor control pins
-        self.pwmA = PWMOutputDevice(EnaA)
-        self.in1A = DigitalOutputDevice(In1A)
-        self.in2A = DigitalOutputDevice(In2A)
-
-        # Right motor control pins
-        self.pwmB = PWMOutputDevice(EnaB)
-        self.in1B = DigitalOutputDevice(In1B)
-        self.in2B = DigitalOutputDevice(In2B)
-
-    def set_pwm(self, left_pwm, right_pwm):
-
-        #Deadband to prevent the motors from responding to very small PWM values that could cause jitter.
-        DEADZONE = 0.002
-
-        if abs(left_pwm) < DEADZONE:
-            self.pwmA.value = 0
-            self.in1A.off()
-            self.in2A.off()
-        else:
-            self.pwmA.value = abs(left_pwm)
-            self.in1A.value = left_pwm >  0
-            self.in2A.value = left_pwm < 0
-
-        if abs(right_pwm) < DEADZONE:
-            self.pwmB.value = 0
-            self.in1B.off()
-            self.in2B.off()
-        else:
-            self.pwmB.value = abs(right_pwm)
-            self.in1B.value = right_pwm >  0
-            self.in2B.value = right_pwm < 0
-
-        #self.node.get_logger().info(f"Left Motor PWM: Speed={left_pwm}, Right Motor PWM: Speed={right_pwm}")
-
-    def stop(self):
-        # Stop both motors
-        self.pwmA.value = 0
-        self.pwmB.value = 0
-        self.in1A.off()
-        self.in2A.off()
-        self.in1B.off()
-        self.in2B.off()
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = MotorControlNode()
-
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.stop_motors()
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/build/robobin/build/lib/robobin/encoder.py b/ros2/build/robobin/build/lib/robobin/encoder.py
deleted file mode 100644
index f646d3dc16cc781b870f52bdbbfc5b5e6e3cbcd0..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/build/lib/robobin/encoder.py
+++ /dev/null
@@ -1,63 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from std_msgs.msg import Int64
-from gpiozero import RotaryEncoder, InputDevice
-
-
-
-class EncoderReaderNode(Node):
-    def __init__(self):
-        super().__init__('encoder_reader_node')
-
-        motor1A = 5
-        motor1B = 6
-        motor2A = 20
-        motor2B = 21
-
-        self.encoder_left = RotaryEncoder(a = motor1A,b = motor1B, max_steps=0)
-        self.encoder_right = RotaryEncoder(a = motor2A,b = motor2B, max_steps=0)
-
-        # Publishers for encoder steps
-        self.left_encoder_pub = self.create_publisher(Int64, 'left_wheel_steps', 10)
-        self.right_encoder_pub = self.create_publisher(Int64, 'right_wheel_steps', 10)
-
-        # Timer to read encoders
-        self.timer = self.create_timer(0.1, self.publish_encoder_steps)
-
-        self.get_logger().info('Encoder reader node has been started.')
-
-    def publish_encoder_steps(self):
-        # Read encoder steps
-        left_steps = self.encoder_left.steps
-        right_steps = -(self.encoder_right.steps)
-
-        # Create messages
-        left_msg = Int64()
-        left_msg.data = left_steps
-
-        right_msg = Int64()
-        right_msg.data = right_steps
-
-        # Publish messages
-        self.left_encoder_pub.publish(left_msg)
-        self.right_encoder_pub.publish(right_msg)
-
-        # Log the steps
-        #self.get_logger().info(f'Left Steps: {left_steps}, Right Steps: {right_steps}')
-
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = EncoderReaderNode()
-
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/build/robobin/build/lib/robobin/helpers/__init__.py b/ros2/build/robobin/build/lib/robobin/helpers/__init__.py
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/build/robobin/build/lib/robobin/helpers/connection_manager.py b/ros2/build/robobin/build/lib/robobin/helpers/connection_manager.py
deleted file mode 100644
index 0fb010b26ca2d962796eb49eee48ab8836705d9f..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/build/lib/robobin/helpers/connection_manager.py
+++ /dev/null
@@ -1,88 +0,0 @@
-import socket
-import threading
-import time
-import json
-
-class ConnectionManager:
-    def __init__(self, api_node, udp_ip="255.255.255.255", udp_port=5005, listen_port=5006):
-        self.api_node = api_node
-        self.UDP_IP = udp_ip
-        self.UDP_PORT = udp_port
-        self.LISTEN_PORT = listen_port
-        self.stop_event = threading.Event()
-        self.location = [0, 0]  # At some point, this will be retrieved from the navigation node
-                
-    def start(self):
-        """Starts listening for connections and broadcasting presence."""
-        self.listen_thread = threading.Thread(target=self.listen_for_connections)
-        self.broadcast_thread = threading.Thread(target=self.broadcast_presence)
-        self.listen_thread.start()
-        self.broadcast_thread.start()
-
-    def listen_for_connections(self):
-        """Listens for UDP 'CONNECT' messages and sets up TCP connections."""
-        udp_sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
-        udp_sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
-        udp_sock.bind(('', self.LISTEN_PORT))
-
-        while not self.stop_event.is_set():
-            try:
-                data, addr = udp_sock.recvfrom(1024)
-                if data.decode() == "CONNECT":
-                    self.api_node.get_logger().info(f"Received CONNECT message from {addr}")
-                    tcp_sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
-                    tcp_sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
-                    tcp_sock.bind(('', self.LISTEN_PORT))
-                    tcp_sock.listen(1)
-                    client_socket, client_addr = tcp_sock.accept()
-                    self.api_node.get_logger().info(f"Client connected from {client_addr}")
-                    threading.Thread(target=self.api_node.handle_client_connection, args=(client_socket,)).start()
-            except socket.timeout:
-                continue
-            except OSError:
-                break
-
-        udp_sock.close()
-        print("Stopped listening for connections.")
-
-    def broadcast_presence(self):
-        """Broadcasts presence periodically over UDP."""
-        sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
-        sock.setsockopt(socket.SOL_SOCKET, socket.SO_BROADCAST, 1)
-
-        while not self.stop_event.is_set():
-            try:
-                mode = self.api_node.mode
-                
-                # JSON-formatted message
-                message = {
-                    "type": "ROBOBIN_PRESENT",
-                    "data": {
-                        "Location": self.location,
-                        "Mode": mode,
-                       
-                    }
-                }
-
-                # Serialize the JSON message to a string
-                json_message = json.dumps(message).encode('utf-8')
-
-                # Send the JSON message over UDP
-                sock.sendto(json_message, (self.UDP_IP, self.UDP_PORT))
-                self.api_node.get_logger().info("Broadcasting JSON presence.")
-                self.api_node.get_logger().info(f"Location: {self.location}, Mode: {mode}")
-                time.sleep(2)
-            except OSError:
-                break
-
-        sock.close()
-        self.api_node.get_logger().info("Stopped broadcasting presence.")
-    def set_location(self, x, y):
-        """Sets the location of the robot."""
-        self.location = [x, y]
-    def stop(self):
-        """Stops the connection manager."""
-        self.stop_event.set()
-    
-if __name__ == "__main__":
-    ConnectionManager(None).start()
diff --git a/ros2/build/robobin/build/lib/robobin/helpers/graph_maker.py b/ros2/build/robobin/build/lib/robobin/helpers/graph_maker.py
deleted file mode 100644
index 202fc34fbdb12d8307c22f7da6bdfc946c351040..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/build/lib/robobin/helpers/graph_maker.py
+++ /dev/null
@@ -1,112 +0,0 @@
-import json
-import time
-import os
-from realtime_location_cli_only import AnchorTagCLI
-
-class GraphMaker:
-    def __init__(self, port="COM11", testing=False):
-        self.app = AnchorTagCLI(port=port, testing=testing)
-        self.graph = {
-            "name": "Lab 1 Extended",
-            "nodes": [],
-            "connections": []
-        }
-        self.previous_node_index = None
-
-    def call_bpm_and_store_anchors(self):
-        self.app.call_bpm()
-        for name, (x, y) in self.app.anchors.items():
-            self.graph["nodes"].append({
-                "name": name,
-                "x": x,
-                "y": y
-            })
-
-        # Initialize connections matrix with False
-        num_nodes = len(self.graph["nodes"])
-        self.graph["connections"] = [[False] * num_nodes for _ in range(num_nodes)]
-
-        print("Anchor coordinates stored successfully.")
-
-    def start_session(self):
-        print("Waiting for 'start' command...")
-        while True:
-            user_input = input("Enter 'start' to begin adding nodes or 'quit' to exit: ").strip().lower()
-            if user_input == "start":
-                print("Session started. Type 'save' to add nodes, 'finish' to save the graph, or 'quit' to exit.")
-                break
-            elif user_input == "quit":
-                print("Exiting...")
-                exit()
-
-    def add_node_and_connect(self):
-        print(self.app.tag_distances)
-        distances = self.app.serial_buffer.getRangingDistances()
-
-        tag1_x, tag1_y = self.app.update_distances_and_calculate_tags()
-        print(f"{tag1_x}, {tag1_y}")
-        if tag1_x is None or tag1_y is None:
-            print("Failed to determine tag position. Skipping node creation.")
-            return
-
-        new_node_index = len(self.graph["nodes"])
-
-        # Add new node
-        self.graph["nodes"].append({
-            "name": f"Node{new_node_index+1}",
-            "x": tag1_x,
-            "y": tag1_y
-        })
-
-        # Dynamically resize the connections matrix
-        for row in self.graph["connections"]:
-            row.append(False)  # Add a column for the new node
-        self.graph["connections"].append([False] * (new_node_index + 1))  # Add a new row
-
-        # Update connections
-        if self.previous_node_index is not None:
-            self.graph["connections"][self.previous_node_index][new_node_index] = True
-            self.graph["connections"][new_node_index][self.previous_node_index] = True
-
-        self.previous_node_index = new_node_index
-
-        print(f"Node {new_node_index+1} added at ({tag1_x:.2f}, {tag1_y:.2f}).")
-
-    def save_graph(self):
-        directory = "/Users/paulwinpenny/Documents/GitHub/robobin/Wireless_Communication/UWB/Beacons_tag_position/output"
-        os.makedirs(directory, exist_ok=True)  # Create the directory if it doesn't exist
-        file_path = os.path.join(directory, "graph.json")
-        with open(file_path, "w") as f:
-            json.dump(self.graph, f, indent=2)
-        print(f"Graph saved to '{file_path}'.")
-
-
-    def run(self):
-        while True:
-            user_input = input("Enter command ('bpm', 'start', 'save', 'finish', 'quit'): ").strip().lower()
-            if user_input == "bpm":
-                self.call_bpm_and_store_anchors()
-            elif user_input == "start":
-                self.start_session()
-                while True:
-                    user_input = input("Enter 'save' to add a node, 'finish' to save and exit, or 'quit' to exit: ").strip().lower()
-                    if user_input == "save":
-                        self.add_node_and_connect()
-                    elif user_input == "finish":
-                        self.save_graph()
-                        print("Session finished.")
-                        exit()
-                    elif user_input == "quit":
-                        print("Exiting without saving.")
-                        exit()
-                    else:
-                        print("Invalid command. Try 'save', 'finish', or 'quit'.")
-            elif user_input == "quit":
-                print("Exiting...")
-                break
-            else:
-                print("Invalid command. Try 'bpm', 'start', 'save', 'finish', or 'quit'.")
-
-if __name__ == "__main__":
-    graph_maker = GraphMaker(port="/dev/tty.usbmodem14101", testing=False)
-    graph_maker.run()
diff --git a/ros2/build/robobin/build/lib/robobin/helpers/message_handler.py b/ros2/build/robobin/build/lib/robobin/helpers/message_handler.py
deleted file mode 100644
index 72ca4a5795a8a5190e77e67e41b42bfa8d4e3a11..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/build/lib/robobin/helpers/message_handler.py
+++ /dev/null
@@ -1,193 +0,0 @@
-# robobin/message_handler.py
-import time
-import json
-
-import os
-class MessageHandler:
-    def __init__(self, api_node, testing=False):
-        self.api_node = api_node
-        self.testing = testing
-        self.handlers = {
-            "PING": self.handle_ping,
-            "TIME": self.handle_time_request,
-            "MANUALCTRL": self.handle_manual_control,
-            "SETMODE": self.handle_set_mode,
-            "STOP": self.handle_stop,
-            "CALLME": self.handle_call_me,
-            "BPM": self.handle_call_bpm,
-            "REQMAP": self.handle_request_map,
-        }
-
-    def handle_message(self, client_socket, raw_message):
-        """Parses the incoming message and routes the command to the appropriate handler."""
-        command, *args = raw_message.split(" ", 1)
-        #self.api_node.logger.info(f"Received command: {command}")
-        #self.api_node.logger.info(f"Received arguments: {args}")
-        data = args[0] if args else None
-        handler = self.handlers.get(command, self.handle_unknown_message)
-        return handler(client_socket, data)
-    
-    def handle_call_me(self, client_socket, message):
-        #Message says  CALLME,(212.9638, 283.98108), extract location and ip address
-        if client_socket is None:
-            ip = "Fake IP"
-        else:
-            ip = client_socket.getpeername()[0]
-        print(message)
-        location = message.strip() # Remove parentheses
-        location = f"{location}"  # Add parentheses back for proper formatting
-        
-        for existing_ip, _ in self.api_node.called_locations:
-            if existing_ip == ip:
-                client_socket.sendall(b"User already requested location")
-                return None  # IP already in the list, exit early
-
-        self.api_node.called_locations.append((ip, location))
-    
-        response = f"Queue Position = {len(self.api_node.called_locations)-1}".encode()
-        client_socket.sendall(response)
-        print("nav_command", location)
-        return "nav_command", location
-    
-    def handle_stop(self, client_socket, _):
-        """Handles the STOP command."""
-        response = b"Stopping the robot"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        return "cmd_vel", (0.0, 0.0)
-    
-    def handle_ping(self, client_socket, _):
-        """Responds with a PONG message."""
-        response = b"PONG"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-
-        return None
-    def handle_set_mode(self, client_socket, message):
-        """Handles mode setting commands."""
-        response = f"Setting mode to {message}".encode()
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        self.api_node.mode = message
-        return None
-    def handle_time_request(self, client_socket, _):
-        """Sends the current server time."""
-        response = time.ctime().encode()
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-
-        return None
-    def handle_call_bpm(self, client_socket, _):
-        """Handles the CALLBPM command."""
-        response = b"Calling BPM, Graph will be reset"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-
-        return "nav_command","BPM"
-    def handle_manual_control(self, client_socket, message):
-        """Handles manual control commands: W, A, S, D."""
-        # W: linear.x = 0.5, angular.z = 0
-        # A: linear.x = 0, angular.z = 0.5
-        # S: linear.x = -0.5, angular.z = 0
-        # D: linear.x = 0, angular.z = -0.5
-        
-        directions = {
-            "W": (0.5, 0),    # Move forward
-            "A": (0, 0.5),    # Turn left
-            "S": (-0.5, 0),   # Move backward
-            "D": (0, -0.5)    # Turn right
-        }
-        
-        # Get direction data and ensure it's a tuple of floats
-        raw_response_data = directions.get(message.strip().upper(), (0, 0))
-        response_data = (float(raw_response_data[0]), float(raw_response_data[1]))  # Explicitly cast to float
-        
-        # Send feedback to the client
-        response = f"Manual control command received: {response_data}".encode()
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        
-        print("Processed manual control command:", response_data)
-        return "cmd_vel", response_data
-
-    def handle_request_map(self, client_socket, _):
-            """Handles the REQMAP command."""
-            # Relative path to the JSON file
-            graph_file_path = os.path.join("src", "robobin", "robobin", "graphs", "graph.json")
-
-            try:
-                # Load the graph JSON file
-                with open(graph_file_path, 'r') as f:
-                    graph_data = json.load(f)
-
-                # Serialize the JSON data to a string
-                graph_json = json.dumps(graph_data)
-                # Send the JSON response back to the client
-                if self.testing:
-                    print("Sending map data:", graph_json)
-                else:
-                    client_socket.sendall(graph_json.encode())
-
-                return None
-
-            except FileNotFoundError:
-                error_message = f"Error: File not found at {graph_file_path}"
-                if self.testing:
-                    print(error_message)
-                else:
-                    client_socket.sendall(error_message.encode())
-
-                return None
-
-            except json.JSONDecodeError as e:
-                error_message = f"Error: Failed to decode JSON - {str(e)}"
-                if self.testing:
-                    print(error_message)
-                else:
-                    client_socket.sendall(error_message.encode())
-
-                return None
-
-            except Exception as e:
-                error_message = f"Error: {str(e)}"
-                if self.testing:
-                    print(error_message)
-                else:
-                    client_socket.sendall(error_message.encode())
-
-                return None
-    def handle_unknown_message(self, client_socket, _):
-        """Handles unknown commands."""
-        response = b"Unknown command"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        return None
-    
-# Test class without api_node and with testing enabled
-if __name__ == "__main__":
-    message_handler = MessageHandler(None, testing=True)
-    assert message_handler.handle_message(None, "PING") is None
-    assert message_handler.handle_message(None, "TIME") is None
-    assert message_handler.handle_message(None, "MANUALCTRL W") == ("cmd_vel", (0.5, 0))
-    assert message_handler.handle_message(None, "MANUALCTRL A") == ("cmd_vel", (0, 0.5))
-    assert message_handler.handle_message(None, "MANUALCTRL S") == ("cmd_vel", (-0.5, 0))
-    assert message_handler.handle_message(None, "MANUALCTRL D") == ("cmd_vel", (0, -0.5))
-
-    assert message_handler.handle_message(None, "STOP") == ("cmd_vel", (0.0, 0.0))
-    assert message_handler.handle_message(None, "CALLME (212.9638, 283.98108)") == ("nav_command", "(212.9638, 283.98108)")
-    assert message_handler.handle_message(None, "UNKNOWN") is None
-    assert message_handler.handle_message(None, "REQMAP") is None
\ No newline at end of file
diff --git a/ros2/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py b/ros2/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py
deleted file mode 100644
index 2c9284f5b76954d74374a8da44127e6f7db673fe..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py
+++ /dev/null
@@ -1,279 +0,0 @@
-import time
-import numpy as np
-import serial
-from scipy.optimize import least_squares
-
-# Define test values at the top of the file for easy modification
-TEST_MEASURED_DISTANCES = [302, 463, 286, 304, 418, 328]
-TEST_TAG1_DISTANCES = [22, 107, 246, 295]
-TEST_TAG2_DISTANCES = [100, 100, 100, 100]
-
-class SerialBuffer:
-    def __init__(self, port):
-        self.ser = serial.Serial(port, 115200, timeout=1)
-
-    def readFromDevice(self, expectedLines=1):
-        lines = []
-        # Attempt to read expected lines; if device is slow, you may need retries
-        while len(lines) < expectedLines:
-            if self.ser.in_waiting:
-                line = self.ser.readline().decode().strip()
-                if line:
-                    lines.append(line)
-            else:
-                time.sleep(0.01)
-        return lines
-
-    def getBeaconPositioningDistances(self):
-        """Reads the measured distances (A,E,D,B,F,C) from the device."""
-        self.writeToDevice("bpm")
-        buffer = self.readFromDevice(1)[0]
-        values = list(map(float, buffer.split(" ")))
-        return values
-
-    def getRangingDistances(self):
-        """Reads the distances from the tags to the anchors."""
-        self.writeToDevice("rng")
-        lines = self.readFromDevice(2)
-        print(lines)
-        distances = []
-        # First line: Tag 1 distances
-        distances.append(list(map(float, lines[0][1:].split(" "))))
-        # Second line: Tag 2 distances or "0"
-        if lines[1] != "1":
-            distances.append(list(map(float, lines[1][1:].split(" "))))
-        else:
-            distances.append(None)
-        return distances
-
-    def writeToDevice(self, value):
-        self.ser.write((value + "\n").encode())
-
-    def __del__(self):
-        print("Closing port")
-        self.ser.close()
-
-
-class AnchorTagCLI:
-    def __init__(self, port="/dev/tty.usbmodem14101", testing=False):
-        self.testing = testing
-        self.serial_buffer = SerialBuffer(port)
-
-        # Distances between anchors (A,E,D,B,F,C)
-        # Corresponding to the measured_distances in original code.
-        self.measured_distances = [0.0]*6
-
-        # Distances from Tag 1 to anchors: A1, A2, A3, A4
-        self.tag_distances = {"A1": 0.0, "A2": 0.0, "A3": 0.0, "A4": 0.0}
-
-        # Distances from Tag 2 to anchors: A1, A2, A3, A4
-        self.tag2_distances = {"A1": 0.0, "A2": 0.0, "A3": 0.0, "A4": 0.0}
-
-        self.anchors = {}
-        self.anchorHeight = 250
-        self.anchors_coords_known = False
-
-        if self.testing:
-            # Set predefined test distances
-            for i, dist in enumerate(TEST_MEASURED_DISTANCES):
-                self.measured_distances[i] = dist
-
-            for (anchor, dist) in zip(self.tag_distances.keys(), TEST_TAG1_DISTANCES):
-                self.tag_distances[anchor] = dist
-
-            for (anchor, dist) in zip(self.tag2_distances.keys(), TEST_TAG2_DISTANCES):
-                self.tag2_distances[anchor] = dist
-
-    def determine_anchor_coords(self):
-        try:
-            measured_distances = np.array(self.measured_distances)
-            y_A = measured_distances[2]  # Distance from A to D
-
-            # Guess for B based on distance A-B and B-D
-            x_B = measured_distances[0] / 2
-            y_B = measured_distances[4] / 2 + 200  # Start y_B above y_C
-
-            # Guess for C with symmetrical logic
-            x_C = -measured_distances[5] / 2  # Allow for negative x_C
-            y_C = -measured_distances[1] / 2  # Allow for negative y_C
-
-            initial_guess = [x_B, y_B, x_C, y_C, y_A]
-
-            min_dist = min(measured_distances)
-            max_dist = max(measured_distances)
-            lower_bounds = [-max_dist, -max_dist, -max_dist, -max_dist, min_dist / 2]
-            upper_bounds = [max_dist * 1.5 for i in range(5)]
-
-            def error_function(variables, measured):
-                x_B, y_B, x_C, y_C, y_A = variables
-
-                # Map measured distances to a, e, d, b, f, c
-                a_measured, e_measured, d_measured, b_measured, f_measured, c_measured = measured
-
-                # Compute each distance
-                a_calc = np.sqrt((x_B - 0)**2 + (y_B - y_A)**2)  # A-B
-                b_calc = np.sqrt((x_C - x_B)**2 + (y_C - y_B)**2)  # B-C
-                c_calc = np.sqrt(x_C**2 + y_C**2)                 # C-D
-                d_calc = y_A                                      # A-D
-                e_calc = np.sqrt(x_C**2 + (y_C - y_A)**2)         # A-C
-                f_calc = np.sqrt(x_B**2 + y_B**2)                 # B-D
-
-                # Residuals
-                r_a = a_calc - a_measured
-                r_b = b_calc - b_measured
-                r_c = c_calc - c_measured
-                r_d = d_calc - d_measured
-                r_e = e_calc - e_measured
-                r_f = f_calc - f_measured
-
-                # Add a smoother penalty if y_B <= y_C
-                penalty = 1e3 * max(0, y_C - y_B + 10)  # Soft penalty to enforce constraint
-
-                return [r_a, r_b, r_c, r_d, r_e, r_f, penalty]
-
-            result = least_squares(error_function, initial_guess, args=(measured_distances,), bounds=(lower_bounds, upper_bounds), loss='soft_l1')
-
-            x_B, y_B, x_C, y_C, y_A = result.x
-            self.anchors = {
-                "A1": (0, y_A, self.anchorHeight),
-                "A2": (x_B, y_B, self.anchorHeight),
-                "A3": (x_C, y_C, self.anchorHeight),
-                "A4": (0, 0, self.anchorHeight)
-            }
-            return {k: (round(v[0], 2), round(v[1], 2)) for k, v in self.anchors.items()}
-        except Exception as e:
-            print(f"Error generating anchors: {e}")
-
-    def calculate_tag_coordinates(self, tag_distances):
-        if not self.anchors_coords_known or len(self.anchors) < 3:
-            return None, None
-     
-        available_beacons = []
-        available_distances = []
-        for key in tag_distances.keys():
-            d = max(float(tag_distances[key]), 0)
-            available_distances.append(d)
-            available_beacons.append(self.anchors[key])
-
-        if len(available_beacons) < 3:
-            return None, None
-
-        heights = []
-        for (bx, by, bz), d_measured in zip(available_beacons, available_distances):
-            horizontal_distance = np.sqrt((bx - 0)**2 + (by - 0)**2)  # Assume tag starts at (0, 0)
-            estimated_z = np.sqrt(max(0, d_measured**2 - horizontal_distance**2))  # Ensure non-negative
-            heights.append(bz - estimated_z)  # Estimate tag height relative to beacon
-
-        initial_z = max(0, min(self.anchorHeight, np.mean(heights)))  # Constrain height to [0, 200]
-        
-        beacon_xs = [b[0] for b in available_beacons]
-        beacon_ys = [b[1] for b in available_beacons]
-        initial_guess = [np.mean(beacon_xs), np.mean(beacon_ys), initial_z]
-
-        # Define bounds for the tag position
-        x_min = min(beacon_xs) - 1000  # Add a small margin around the beacons
-        x_max = max(beacon_xs) + 1000
-        y_min = min(beacon_ys) - 1000
-        y_max = max(beacon_ys) + 1000
-        z_min = 0.0  # Tag's height cannot be below the ground
-        z_max = self.anchorHeight  # Tag's height cannot exceed the beacon height
-        bounds = ([x_min, y_min, z_min], [x_max, y_max, z_max])
-        
-        def error_function(vars):
-            x, y, z= vars
-            residuals = []
-            for (bx, by, bz), d_measured in zip(available_beacons, available_distances):
-                d_computed = np.sqrt((x - bx)**2 + (y - by)**2 + (z - bz)**2)
-                residuals.append(d_computed - d_measured)
-            return residuals
-
-        result = least_squares(error_function, initial_guess, bounds=bounds, loss='soft_l1')
-        # self.get_logger().info(f"Optimization result: {result.x}")
-        return tuple(result.x)
-
-
-    def call_bpm(self):
-        if self.testing:
-            beacon_distances = TEST_MEASURED_DISTANCES
-        else:
-            beacon_distances = self.serial_buffer.getBeaconPositioningDistances()
-
-        for i, distance in enumerate(beacon_distances):
-            if i < len(self.measured_distances):
-                self.measured_distances[i] = distance
-
-        determined_anchor_coords = self.determine_anchor_coords()
-        if determined_anchor_coords:
-            self.anchors_coords_known = True
-            print("Anchor coordinates determined:")
-            for anchor, coords in determined_anchor_coords.items():
-                print(f"{anchor}: {coords}")
-
-    def update_distances_and_calculate_tags(self):
-        if not self.anchors_coords_known:
-            return
-
-        if self.testing:
-            ranging_distances = [TEST_TAG1_DISTANCES, TEST_TAG2_DISTANCES]
-        else:
-            ranging_distances = self.serial_buffer.getRangingDistances()
-
-        # Update tag 1 distances
-        if ranging_distances[0] is not None:
-            for i, distance in enumerate(ranging_distances[0]):
-                anchor = list(self.tag_distances.keys())[i]
-                self.tag_distances[anchor] = distance
-
-        # Update tag 2 distances
-        if ranging_distances[1] is not None:
-            for i, distance in enumerate(ranging_distances[1]):
-                anchor = list(self.tag2_distances.keys())[i]
-                self.tag2_distances[anchor] = distance
-
-        # Now calculate both tags
-        tag1_x, tag1_y, tag1_z = self.calculate_tag_coordinates(self.tag_distances)
-        valid_tag2_distances = [dist for dist in self.tag2_distances.values() if dist > 0]
-
-        # Check if there are enough valid distances for Tag 2
-        if len(valid_tag2_distances) < 3:
-            print(f"Insufficient valid distances for Tag 2: {len(valid_tag2_distances)} provided.")
-            tag2_x, tag2_y, tag2_z = None, None, None
-        else:
-            tag2_x, tag2_y, tag2_z = self.calculate_tag_coordinates(self.tag2_distances)
-
-        print("Tag Positions:")
-        if tag1_x is not None and tag1_y is not None:
-            print(f"Tag 1: ({tag1_x:.2f}, {tag1_y:.2f}, {tag1_z:.2f})")
-        else:
-            print("Tag 1: Not enough data")
-
-        if tag2_x is not None and tag2_y is not None:
-            print(f"Tag 2: ({tag2_x:.2f}, {tag2_y:.2f}, {tag2_z:.2f})")
-        else:
-            print("Tag 2: Not enough data")
-
-      
-        if tag1_x is not None and tag1_y is not None and tag2_x is not None and tag2_y is not None:
-            dx = tag2_x - tag1_x
-            dy = tag2_y - tag1_y
-            dz = tag2_z - tag1_z
-            displacement = np.sqrt(dx**2 + dy**2 + dz**2)
-            angle_deg = np.degrees(np.arctan2(dy, dx))
-            if angle_deg < 0:
-                angle_deg += 360
-            print(f"Direction from Tag1 to Tag2: dx={dx:.2f}, dy={dy:.2f}, displacement={displacement:.2f}, angle={angle_deg:.2f}°")
-        return tag1_x, tag1_y
-
-if __name__ == "__main__":
-    app = AnchorTagCLI(port="/dev/tty.usbmodem14101", testing=False)
-    while True:
-        user_input = input("Enter command ('bpm' to set anchors, or 'quit' to exit): ").strip().lower()
-        if user_input == "bpm":
-            app.call_bpm()
-            print("Switching to continuous ranging updates (simulating 'rng' messages)...")
-            while True:
-                app.update_distances_and_calculate_tags()
-                time.sleep(1)
-        elif user_input == "quit":
-            print("Exiting program.")
-            break
\ No newline at end of file
diff --git a/ros2/build/robobin/build/lib/robobin/imu_node.py b/ros2/build/robobin/build/lib/robobin/imu_node.py
deleted file mode 100644
index d20c2dad0c8ab6525395a00d74ce5833f1fa2d94..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/build/lib/robobin/imu_node.py
+++ /dev/null
@@ -1,95 +0,0 @@
-#!/usr/bin/env python3
-
-import rclpy
-from rclpy.node import Node
-from sensor_msgs.msg import Imu
-from smbus2 import SMBus
-import time
-import math
-
-class BNO055Publisher(Node):
-    def __init__(self):
-        super().__init__('imu_node')
-        self.publisher_ = self.create_publisher(Imu, 'imu', 10)
-        self.timer = self.create_timer(0.1, self.timer_callback)
-        self.bus = SMBus(1)
-        self.address = 0x28
-        self.init_bno055()
-        time.sleep(1)
-
-    def write_register(self, register, value):
-        self.bus.write_byte_data(self.address, register, value)
-
-    def read_register(self, register, length=1):
-        if length == 1:
-            return self.bus.read_byte_data(self.address, register)
-        else:
-            return self.bus.read_i2c_block_data(self.address, register, length)
-
-    def init_bno055(self):
-        # Switch to CONFIG mode
-        self.write_register(0x3D, 0x00)
-        time.sleep(0.05)
-        # Set power mode to Normal
-        self.write_register(0x3E, 0x00)
-        # Set to NDOF mode
-        self.write_register(0x3D, 0x0C)
-        time.sleep(0.5)
-
-    def read_euler_angles(self):
-        data = self.read_register(0x1A, 6)
-        yaw = (data[1] << 8) | data[0]
-        roll = (data[3] << 8) | data[2]
-        pitch = (data[5] << 8) | data[4]
-        yaw = yaw if yaw < 32768 else yaw - 65536
-        roll = roll if roll < 32768 else roll - 65536
-        pitch = pitch if pitch < 32768 else pitch - 65536
-        yaw = yaw / 16.0
-        roll = roll / 16.0
-        pitch = pitch / 16.0
-        return yaw, pitch, roll
-
-    def timer_callback(self):
-        yaw, pitch, roll = self.read_euler_angles()
-        imu_msg = Imu()
-        imu_msg.header.stamp = self.get_clock().now().to_msg()
-        imu_msg.header.frame_id = 'imu_link'
-        # Convert degrees to radians
-        yaw_rad = -(math.radians(yaw))
-        roll_rad = -(math.radians(pitch))
-        pitch_rad = -(math.radians(roll))
-        # Compute quaternion
-        cy = math.cos(yaw_rad * 0.5)
-        sy = math.sin(yaw_rad * 0.5)
-        cp = math.cos(pitch_rad * 0.5)
-        sp = math.sin(pitch_rad * 0.5)
-        cr = math.cos(roll_rad * 0.5)
-        sr = math.sin(roll_rad * 0.5)
-        imu_msg.orientation.w = cr * cp * cy + sr * sp * sy
-        imu_msg.orientation.x = sr * cp * cy - cr * sp * sy
-        imu_msg.orientation.y = cr * sp * cy + sr * cp * sy
-        imu_msg.orientation.z = cr * cp * sy - sr * sp * cy
-
-        imu_msg.orientation_covariance = [0.0025, 0, 0,
-                                  0, 0.0025, 0,
-                                  0, 0, 0.0025]
-        imu_msg.angular_velocity_covariance = [0.02, 0, 0,
-                                            0, 0.02, 0,
-                                            0, 0, 0.02]
-        imu_msg.linear_acceleration_covariance = [0.04, 0, 0,
-                                                0, 0.04, 0,
-                                                0, 0, 0.04]
-
-
-        self.publisher_.publish(imu_msg)
-        #self.get_logger().info(f'Publishing: Yaw={yaw:.2f}, Pitch={pitch:.2f}, Roll={roll:.2f}')
-
-def main(args=None):
-    rclpy.init(args=args)
-    bno055_publisher = BNO055Publisher()
-    rclpy.spin(bno055_publisher)
-    bno055_publisher.destroy_node()
-    rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
\ No newline at end of file
diff --git a/ros2/build/robobin/build/lib/robobin/motor_control_node.py b/ros2/build/robobin/build/lib/robobin/motor_control_node.py
deleted file mode 100644
index 25786c4a14305145926601ce96e723029b42c750..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/build/lib/robobin/motor_control_node.py
+++ /dev/null
@@ -1,73 +0,0 @@
-#!/usr/bin/env python3
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Twist
-from gpiozero import PWMOutputDevice
-from time import sleep
-
-class Motor:
-    def __init__(self, node, EnaA, In1A, In2A, EnaB, In1B, In2B):
-        self.node = node
-        self.pwmA = PWMOutputDevice(EnaA)
-        self.in1A = PWMOutputDevice(In1A)
-        self.in2A = PWMOutputDevice(In2A)
-        self.pwmB = PWMOutputDevice(EnaB)
-        self.in1B = PWMOutputDevice(In1B)
-        self.in2B = PWMOutputDevice(In2B)
-
-    def move(self, speed=0.0, turn=0.0):
-        speed = max(-1, min(1, speed))
-        turn = max(-1, min(1, turn))
-
-        leftSpeed = speed - turn
-        rightSpeed = speed + turn
-        '''
-        left_speed = self.desired_speed - (turn_rate * self.motor.wheel_base / 2)
-        right_speed = self.desired_speed + (turn_rate * self.motor.wheel_base / 2)
-        '''
-
-        leftSpeed = max(-1, min(1, leftSpeed))
-        rightSpeed = max(-1, min(1, rightSpeed))
-
-        self.pwmA.value = abs(leftSpeed)
-        self.in1A.value = leftSpeed <=  0
-        self.in2A.value = leftSpeed > 0
-
-        self.pwmB.value = abs(rightSpeed)
-        self.in1B.value = rightSpeed > 0
-        self.in2B.value = rightSpeed <= 0
-
-        self.node.get_logger().info(f"Left Motor: Speed={leftSpeed}, Right Motor: Speed={rightSpeed}")
-
-
-    def stop(self):
-        self.pwmA.value = 0
-        self.pwmB.value = 0
-
-class MotorControlNode(Node):
-    def __init__(self):
-        super().__init__('motor_control_node')
-        self.get_logger().info("hello")
-        self.motor = Motor(self, 14, 15, 18, 17, 22, 27)
-        self.subscription = self.create_subscription(
-            Twist,
-            'cmd_vel',
-            self.cmd_vel_callback,
-            10
-        )
-
-    def cmd_vel_callback(self, msg):
-        linear_x = msg.linear.x
-        angular_z = msg.angular.z
-        self.motor.move(speed=linear_x, turn=angular_z)
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = MotorControlNode()
-    rclpy.spin(node)
-    rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
-
-#colcon build --symlink-install
\ No newline at end of file
diff --git a/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py b/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py
deleted file mode 100644
index 60ee12d31513bf73cce1e2702d5b3ea91a814923..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py
+++ /dev/null
@@ -1,318 +0,0 @@
-import json
-import os
-import time
-import numpy as np
-from scipy.optimize import least_squares
-from geometry_msgs.msg import Point
-import rclpy
-from rclpy.node import Node
-from std_msgs.msg import String
-from sensor_msgs.msg import Imu
-import tf_transformations
-
-class SerialBuffer:
-    def __init__(self, port):
-        import serial
-        self.ser = serial.Serial(port, 115200, timeout=1)
-
-    def readFromDevice(self, expectedLines=1):
-        lines = []
-        while len(lines) < expectedLines:
-            if self.ser.in_waiting:
-                line = self.ser.readline().decode().strip()
-                if line:
-                    lines.append(line)
-            else:
-                time.sleep(0.01)
-        return lines
-
-    def getBeaconPositioningDistances(self):
-        # return [302, 463, 286, 304, 418, 328]
-        self.writeToDevice("bpm")
-        buffer = self.readFromDevice(1)[0]
-        values = list(map(float, buffer.split(" ")))
-        
-        return values
-
-    def getRangingDistances(self):
-        
-        self.writeToDevice("rng")
-        lines = self.readFromDevice(2)
-
-        print(lines)
-        distances = []
-        distances.append(list(map(float, lines[0][1:].split(" "))))
-        if lines[1] != "1":
-           distances.append(list(map(float, lines[1][1:].split(" "))))
-        else:
-            distances.append(None)
-        return distances
-
-    def writeToDevice(self, value):
-        self.ser.write((value + "\n").encode())
-
-    def __del__(self):
-        self.ser.close()
-
-class UWBNode(Node):
-    def __init__(self):
-        super().__init__('uwb_navigation_node')
-
-        self.publisher = self.create_publisher(Point, '/tag1_location', 10)
-        self.subscription = self.create_subscription(String, '/nav_command', self.handle_nav_command, 10)
-        self.imu_subscription = self.create_subscription(Imu, '/imu', self.handle_imu, 10)
-
-        self.current_yaw = None  # Store the current IMU yaw
-        self.uwb_to_imu_offset = None  # Offset between UWB and IMU heading
-        
-        self.serial_buffer = SerialBuffer("/dev/ttyACM0")
-        self.anchors = {}
-        self.anchors_coords_known = False
-        self.previous_tag1_position = None
-        working_directory = os.getcwd()
-        anchors_file_path =  os.abspath(os.path.join(working_directory, "src", "robobin", "robobin", "graphs", "anchors.json"))
-        if os.path.exists(anchors_file_path):
-            try:
-                with open(anchors_file_path, 'r') as f:
-                    anchors_data = json.load(f)
-                    self.anchors = anchors_data
-                    self.anchors_coords_known = True
-                    self.get_logger().info("Anchor coordinates loaded from anchors.json.")
-            except Exception as e:
-                self.get_logger().error(f"Failed to load anchors.json: {e}")
-                self.anchors_coords_known = False
-        else:
-            self.get_logger().warning("anchors.json not found, anchor coordinates not known.")
-            self.get_logger().warning(f"(should be at {anchors_file_path})")
-            self.anchors_coords_known = False
-
-        # Timer to continuously fetch and publish positions
-        self.timer = self.create_timer(1.0, self.update_positions)
-
-    def call_bpm(self):
-        try:
-            beacon_distances = self.serial_buffer.getBeaconPositioningDistances()
-            self.get_logger().info(f"Retreived values {beacon_distances }")
-            self.determine_anchor_coords(beacon_distances)
-            self.anchors_coords_known = True
-            self.get_logger().info("Anchor coordinates determined.")
-            anchors_file_path = os.path.join("src", "robobin", "robobin", "graphs", "anchors.json")
-            try:
-                with open(anchors_file_path, 'w') as f:
-                    json.dump(self.anchors, f)
-                self.get_logger().info("Anchor coordinates saved to anchors.json.")
-
-
-                graph = {
-                    "name": "Lab 1 Extended",
-                    "nodes": [],
-                    "connections": []
-                }
-
-                # Populate nodes with anchor data
-                anchor_names = ["A1", "A2", "A3", "A4"]
-                for i, (key, coords) in enumerate(self.anchors.items()):
-                    graph["nodes"].append({"name": anchor_names[i], "x": coords[0], "y": coords[1]})
-
-                # Create a fully connected adjacency matrix (all nodes connected)
-                num_nodes = len(graph["nodes"])
-                graph["connections"] = [[True if i != j else False for j in range(num_nodes)] for i in range(num_nodes)]
-
-                # Save graph to file
-                graph_file_path = os.path.join("src", "robobin", "robobin", "graphs", "graph.json")
-                with open(graph_file_path, 'w') as f:
-                    json.dump(graph, f, indent=2)
-                self.get_logger().info("Graph saved to graph.json.")
-
-       
-            except Exception as e:
-                self.get_logger().error(f"Failed to save anchors.json: {e}")
-
-        except Exception as e:
-            self.get_logger().error(f"Failed to determine anchors: {e}")
-
-    def handle_imu(self, msg):
-        # Extract yaw from quaternion
-        orientation_q = msg.orientation
-        orientation_list = [orientation_q.x, orientation_q.y, orientation_q.z, orientation_q.w]
-        _, _, yaw = tf_transformations.euler_from_quaternion(orientation_list)
-        
-        self.current_yaw = yaw  # Update current yaw
-        self.get_logger().info(f"IMU Yaw: {yaw:.2f} radians")
-    def determine_anchor_coords(self, measured_distances):
-        measured_distances = np.array(measured_distances)
-
-        initial_guess = [120, 100, 150, 200, 50]
-        bounds = ([0, 0, 0, 0, 0], [1000, 1000, 1000, 1000, 1000])
-
-        def error_function(variables, measured):
-            x_B, y_B, x_C, y_C, y_A = variables
-            a_calc = np.sqrt((x_B - 0)**2 + (y_B - y_A)**2)  # A-B
-            b_calc = np.sqrt((x_C - x_B)**2 + (y_C - y_B)**2)  # B-C
-            c_calc = np.sqrt(x_C**2 + y_C**2)  # C-D
-            d_calc = y_A  # A-D
-            e_calc = np.sqrt(x_C**2 + (y_C - y_A)**2)  # A-C
-            f_calc = np.sqrt(x_B**2 + y_B**2)  # B-D
-
-            return [
-                a_calc - measured[0],
-                b_calc - measured[3],
-                c_calc - measured[5],
-                d_calc - measured[2],
-                e_calc - measured[1],
-                f_calc - measured[4]
-            ]
-
-        result = least_squares(
-            error_function,
-            initial_guess,
-            args=(measured_distances,),
-            bounds=bounds,
-            loss='soft_l1'
-        )
-        x_B, y_B, x_C, y_C, y_A = result.x
-        self.anchors = {
-            "A1": (0, y_A),
-            "A2": (x_B, y_B),
-            "A3": (x_C, y_C),
-            "A4": (0, 0)
-        }
-
-    def calculate_tag_coordinates(self, tag_distances):
-        # self.get_logger().info(f"Tag distances: {tag_distances}")
-        if not self.anchors_coords_known or len(self.anchors) < 3:
-            self.get_logger().warning("Anchor coordinates not known.")
-            return None
-        
-        available_beacons = []
-        available_distances = []
-
-        for key, dist in tag_distances.items():
-            if dist > 0:
-                available_distances.append(dist)
-                available_beacons.append(self.anchors[key])
-
-        if len(available_beacons) < 3:
-            return None
-
-        def error_function(vars):
-            x, y = vars
-            residuals = []
-            for (bx, by), d_measured in zip(available_beacons, available_distances):
-                d_computed = np.sqrt((x - bx)**2 + (y - by)**2)
-                residuals.append(d_computed - d_measured)
-            return residuals
-
-        beacon_xs = [b[0] for b in available_beacons]
-        beacon_ys = [b[1] for b in available_beacons]
-        initial_guess = [np.mean(beacon_xs), np.mean(beacon_ys)]
-
-        bounds = (
-            [min(beacon_xs) - 100, min(beacon_ys) - 100],
-            [max(beacon_xs) + 100, max(beacon_ys) + 100]
-        )
-
-        result = least_squares(error_function, initial_guess, bounds=bounds, loss='soft_l1')
-        self.get_logger().info(f"Optimization result: {result.x}")
-        return tuple(result.x)
-
-    def update_positions(self):
-        self.get_logger().info("Updating positions...")
-        #self.get_logger().info(f"Is anchor coords known: {self.anchors_coords_known}")
-        if self.anchors_coords_known:
-            
-            
-
-            try:
-                ranging_distances = self.serial_buffer.getRangingDistances()
-                self.get_logger().info(f"Ranging Distances {ranging_distances}")
-                tag1_distances = ranging_distances[0]
-                self.get_logger().info(f"Tag1 distances {tag1_distances}")
-                tag_distances_dict = {
-                    "A1": tag1_distances[0],
-                    "A2": tag1_distances[1],
-                    "A3": tag1_distances[2],
-                    "A4": tag1_distances[3]
-                }
-                self.get_logger().info(f"Tag distances: {tag_distances_dict}")
-                tag1_position = self.calculate_tag_coordinates(tag_distances_dict)
-
-                if tag1_position is not None :
-                    self.previous_tag1_position = tag1_position
-                    position_msg = Point(x=tag1_position[0], y=tag1_position[1], z=0.0)
-                    self.publisher.publish(position_msg)
-                    #self.get_logger().info(f"Published new Tag 1 position: {tag1_position}")
-
-                #self.get_logger().info(f"Tag 1 position: {tag1_position}")
-                tag2_distances = ranging_distances[1]
-                self.get_logger().info(f"Tag2 distances {tag2_distances}")
-                tag2_position = None
-                if tag2_distances is not None:
-                    
-                    tag2_distances_dict = {
-                        "A1": tag2_distances[0],
-                        "A2": tag2_distances[1],
-                        "A3": tag2_distances[2],
-                        "A4": tag2_distances[3]
-                    }
-                    tag2_position = self.calculate_tag_coordinates(tag2_distances_dict)
-                else:
-                    self.get_logger().warning("Tag 2 is not known")
-      
-
-                # Calculate angle between tag1 and tag2, then print out the angle. @TODO: Move the bin forward to see which direction we are facing, then match the angle with the IMU yaw. This will then mean we can calculate the offset between the UWB and IMU heading.
-                if tag2_position is not None:
-                    displacement_x = tag2_position[0] - tag1_position[0]
-                    displacement_y = tag2_position[1] - tag1_position[1]
-                    
-                    # Calculate angle and distance
-                    displacement_angle = np.arctan2(displacement_y, displacement_x)  
-                    displacement_distance = np.sqrt(displacement_x**2 + displacement_y**2)
-                    
-                    self.get_logger().info(f"Displacement: dx={displacement_x:.2f}, dy={displacement_y:.2f}")
-                    self.get_logger().info(f"Displacement Angle: {np.degrees(displacement_angle):.2f}°")
-                    self.get_logger().info(f"Displacement Distance: {displacement_distance:.2f} units")
-                
-
-            except Exception as e:
-                self.get_logger().error(f"Error updating positions: {e}")
-    def clear_graph(self):
-        self.anchors_coords_known = False
-        self.anchors = {}
-        self.previous_tag1_position = None
-        graph_file_path = os.path.join("src", "robobin", "robobin", "graphs", "graph.json")
-        default_file_path = os.path.join("src", "robobin", "robobin", "graphs", "default_graph.json")
-        try:
-            with open(default_file_path, 'r') as f:
-                graph_data = json.load(f)
-                with open(graph_file_path, 'w') as f:
-                    json.dump(graph_data, f)
-        except FileNotFoundError:
-            self.get_logger().error(f"Error: File not found at {default_file_path}")
-        except json.JSONDecodeError as e:
-            self.get_logger().error(f"Error: Failed to decode JSON - {str(e)}")
-        except Exception as e:
-            self.get_logger().error(f"Error: {str(e)}")
-
-        self.get_logger().info("Graph cleared.")
-
-
-    def handle_nav_command(self, msg):
-        if msg.data == "BPM":
-            self.clear_graph()
-            self.call_bpm()
-            self.anchors_coords_known = True
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = UWBNode()
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == "__main__":
-    main()
diff --git a/ros2/build/robobin/build/lib/robobin/uwb_pathing_node.py b/ros2/build/robobin/build/lib/robobin/uwb_pathing_node.py
deleted file mode 100644
index dec8b95597d81d37e8cc8f3d74aef15b9c7702c8..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/build/lib/robobin/uwb_pathing_node.py
+++ /dev/null
@@ -1,122 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Twist, Point
-from math import sqrt, pow, atan2, radians, sin, cos
-import time
-
-
-class UWBPathingNode(Node):
-    def __init__(self):
-        super().__init__('uwb_pathing_node')
-
-        # Publisher for cmd_vel
-        self.cmd_vel_pub = self.create_publisher(Twist, '/cmd_vel', 10)
-
-        # Subscriptions
-        self.create_subscription(Point, '/start_location', self.current_location_callback, 10)
-        self.create_subscription(Point, '/target_location', self.target_location_callback, 10)
-
-        # Current and target positions
-        self.current_x = None
-        self.current_y = None
-        self.target_x = None
-        self.target_y = None
-
-        # Navigation thresholds
-        self.distance_threshold = 0.25  # meters
-        self.angle_threshold = radians(0.5)  # radians
-
-        self.kp_linear = 0.5  # Proportional gain for linear movement
-        self.kp_angular = 1.0  # Proportional gain for angular movement
-
-        self.get_logger().info('UWB Pathing Node started and waiting for positions.')
-
-    def current_location_callback(self, msg: Point):
-        """Callback to update the robot's current position."""
-        self.current_x = msg.x
-        self.current_y = msg.y
-        self.get_logger().info(f"Current Location Updated: x={self.current_x:.2f}, y={self.current_y:.2f}")
-        self.check_and_navigate()
-
-    def target_location_callback(self, msg: Point):
-        """Callback to update the target position."""
-        self.target_x = msg.x
-        self.target_y = msg.y
-        self.get_logger().info(f"Target Location Updated: x={self.target_x:.2f}, y={self.target_y:.2f}")
-        self.check_and_navigate()
-
-    def check_and_navigate(self):
-        """Check if both positions are available and navigate to the target."""
-        if self.current_x is not None and self.current_y is not None and self.target_x is not None and self.target_y is not None:
-            self.get_logger().info("Navigating to target...")
-            self.navigate_to_target()
-        else:
-            self.get_logger().warning("Waiting for both current and target positions to be available...")
-
-    def navigate_to_target(self):
-        # Ensure positions are known
-        if self.current_x is None or self.current_y is None or self.target_x is None or self.target_y is None:
-            self.get_logger().warning("Positions not fully known yet.")
-            return
-
-        # Calculate distance and angle to the target
-        displacement_x = self.target_x - self.current_x
-        displacement_y = self.target_y - self.current_y
-        distance_to_target = sqrt(pow(displacement_x, 2) + pow(displacement_y, 2))
-        angle_to_target = atan2(displacement_y, displacement_x)
-
-
-        # Check if we are close enough to the target
-        if distance_to_target <= self.distance_threshold:
-            self.stop_robot()
-            self.get_logger().info("Target reached successfully.")
-            return
-
-        # Calculate yaw error (assuming robot orientation 0 = facing x-axis)
-        # If you don't have actual orientation, you might assume the robot always faces the target directly
-        yaw_error = angle_to_target
-        yaw_error = atan2(sin(yaw_error), cos(yaw_error))  # Normalize angle
-        self.get_logger().info(f"Current Position: x={self.current_x:.2f}, y={self.current_y:.2f}")
-        self.get_logger().info(f"Target Position: x={self.target_x:.2f}, y={self.target_y:.2f}")
-        self.get_logger().info(f"Distance to Target: distance_to_target={distance_to_target:.2f} meters")
-        self.get_logger().info(f"Angle to Target: angle_to_target={angle_to_target:.2f} radians")
-        twist = Twist()
-
-        # Decide on angular velocity first
-        if abs(yaw_error) > self.angle_threshold:
-            angular_speed = self.kp_angular * abs(yaw_error)
-            twist.angular.z = angular_speed if yaw_error > 0 else -angular_speed
-            self.get_logger().info(f"Correcting Heading: yaw_error={yaw_error:.2f} radians")
-        else:
-            # Move forward when aligned with the target
-            linear_speed = self.kp_linear * distance_to_target
-            twist.linear.x = min(0.2, linear_speed)  # Limit max speed
-            self.get_logger().info(f"Moving to Target: distance={distance_to_target:.2f} meters")
-
-        # # Publish movement command
-        # self.cmd_vel_pub.publish(twist)
-
-
-    def stop_robot(self):
-        """Stops the robot by publishing zero velocities."""
-        twist = Twist()
-        self.cmd_vel_pub.publish(twist)
-        time.sleep(0.5)
-        self.get_logger().info("Robot stopped.")
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = UWBPathingNode()
-
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/build/robobin/colcon_build.rc b/ros2/build/robobin/colcon_build.rc
deleted file mode 100644
index 573541ac9702dd3969c9bc859d2b91ec1f7e6e56..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/colcon_build.rc
+++ /dev/null
@@ -1 +0,0 @@
-0
diff --git a/ros2/build/robobin/colcon_command_prefix_setup_py.sh b/ros2/build/robobin/colcon_command_prefix_setup_py.sh
deleted file mode 100644
index f9867d51322a8ef47d4951080db6e3cfd048835e..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/colcon_command_prefix_setup_py.sh
+++ /dev/null
@@ -1 +0,0 @@
-# generated from colcon_core/shell/template/command_prefix.sh.em
diff --git a/ros2/build/robobin/colcon_command_prefix_setup_py.sh.env b/ros2/build/robobin/colcon_command_prefix_setup_py.sh.env
deleted file mode 100644
index c0c0c50a0077091c3194ffd844a41b09aaaabc98..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/colcon_command_prefix_setup_py.sh.env
+++ /dev/null
@@ -1,63 +0,0 @@
-AMENT_PREFIX_PATH=/home/robobin/robobin/ros2/src/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy
-CMAKE_PREFIX_PATH=/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor
-COLCON=1
-COLCON_PREFIX_PATH=/home/robobin/robobin/ros2/src/install:/home/robobin/Robobin_Project/ros2/robobin_main/install
-COLORTERM=truecolor
-DBUS_SESSION_BUS_ADDRESS=unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a
-DBUS_STARTER_ADDRESS=unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a
-DBUS_STARTER_BUS_TYPE=session
-DEBUGINFOD_URLS=https://debuginfod.ubuntu.com
-DESKTOP_SESSION=ubuntu
-DISPLAY=:0
-GDMSESSION=ubuntu
-GNOME_DESKTOP_SESSION_ID=this-is-deprecated
-GNOME_SETUP_DISPLAY=:1
-GNOME_SHELL_SESSION_MODE=ubuntu
-GNOME_TERMINAL_SCREEN=/org/gnome/Terminal/screen/92f2849b_1746_4562_850c_1b14829cbe47
-GNOME_TERMINAL_SERVICE=:1.102
-GSM_SKIP_SSH_AGENT_WORKAROUND=true
-GTK_MODULES=gail:atk-bridge
-GZ_CONFIG_PATH=/opt/ros/jazzy/opt/sdformat_vendor/share/gz
-HOME=/home/robobin
-IM_CONFIG_PHASE=1
-LANG=en_US.UTF-8
-LC_ALL=en_US.UTF-8
-LD_LIBRARY_PATH=/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib
-LESSCLOSE=/usr/bin/lesspipe %s %s
-LESSOPEN=| /usr/bin/lesspipe %s
-LOGNAME=robobin
-LS_COLORS=rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:
-MEMORY_PRESSURE_WATCH=/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/app.slice/app-gnome\x2dsession\x2dmanager.slice/gnome-session-manager@ubuntu.service/memory.pressure
-MEMORY_PRESSURE_WRITE=c29tZSAyMDAwMDAgMjAwMDAwMAA=
-OLDPWD=/home/robobin/robobin/ros2/src
-PATH=/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin
-PWD=/home/robobin/robobin/ros2/build/robobin
-PYTHONPATH=/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages
-QT_ACCESSIBILITY=1
-QT_IM_MODULE=ibus
-ROS_AUTOMATIC_DISCOVERY_RANGE=SUBNET
-ROS_DISTRO=jazzy
-ROS_DOMAIN_ID=3
-ROS_PYTHON_VERSION=3
-ROS_VERSION=2
-SESSION_MANAGER=local/robobin-desktop:@/tmp/.ICE-unix/1594,unix/robobin-desktop:/tmp/.ICE-unix/1594
-SHELL=/bin/bash
-SHLVL=1
-SSH_AUTH_SOCK=/run/user/1002/keyring/ssh
-SYSTEMD_EXEC_PID=1594
-TERM=xterm-256color
-USER=robobin
-USERNAME=robobin
-VTE_VERSION=7600
-WAYLAND_DISPLAY=wayland-0
-XAUTHORITY=/run/user/1002/.mutter-Xwaylandauth.XGQ7Y2
-XDG_CONFIG_DIRS=/etc/xdg/xdg-ubuntu:/etc/xdg
-XDG_CURRENT_DESKTOP=ubuntu:GNOME
-XDG_DATA_DIRS=/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop
-XDG_MENU_PREFIX=gnome-
-XDG_RUNTIME_DIR=/run/user/1002
-XDG_SESSION_CLASS=user
-XDG_SESSION_DESKTOP=ubuntu
-XDG_SESSION_TYPE=wayland
-XMODIFIERS=@im=ibus
-_=/usr/bin/colcon
diff --git a/ros2/build/robobin/install.log b/ros2/build/robobin/install.log
deleted file mode 100644
index a51938fdbb5788d17c7d54571857085aa4a3a666..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/install.log
+++ /dev/null
@@ -1,27 +0,0 @@
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__init__.py
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/api_node.py
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/motor_control_node.cpython-312.pyc
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/__init__.cpython-312.pyc
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_navigation_node.cpython-312.pyc
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/api_node.cpython-312.pyc
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/message_handler.cpython-312.pyc
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/__init__.cpython-312.pyc
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/connection_manager.cpython-312.pyc
-/home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages/robobin
-/home/robobin/robobin/ros2/install/robobin/share/robobin/package.xml
-/home/robobin/robobin/ros2/install/robobin/share/robobin/launch/robobin_launch.py
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/SOURCES.txt
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/top_level.txt
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/PKG-INFO
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/zip-safe
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/requires.txt
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/dependency_links.txt
-/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/entry_points.txt
-/home/robobin/robobin/ros2/install/robobin/lib/robobin/api_node
-/home/robobin/robobin/ros2/install/robobin/lib/robobin/motor_control_node
-/home/robobin/robobin/ros2/install/robobin/lib/robobin/uwb_navigation_node
diff --git a/ros2/build/robobin/prefix_override/__pycache__/sitecustomize.cpython-312.pyc b/ros2/build/robobin/prefix_override/__pycache__/sitecustomize.cpython-312.pyc
deleted file mode 100644
index 7bf811671fae044c6391faa4e7a10c7aad7dfd06..0000000000000000000000000000000000000000
Binary files a/ros2/build/robobin/prefix_override/__pycache__/sitecustomize.cpython-312.pyc and /dev/null differ
diff --git a/ros2/build/robobin/prefix_override/sitecustomize.py b/ros2/build/robobin/prefix_override/sitecustomize.py
deleted file mode 100644
index 6374f9ff7806a2e8442f2c68d74d33bdb8775624..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/prefix_override/sitecustomize.py
+++ /dev/null
@@ -1,4 +0,0 @@
-import sys
-if sys.prefix == '/usr':
-    sys.real_prefix = sys.prefix
-    sys.prefix = sys.exec_prefix = '/home/robobin/robobin/ros2/install/robobin'
diff --git a/ros2/build/robobin/robobin.egg-info/PKG-INFO b/ros2/build/robobin/robobin.egg-info/PKG-INFO
deleted file mode 100644
index 59b425a79a72e98ee9bcafffada085b85d328236..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/robobin.egg-info/PKG-INFO
+++ /dev/null
@@ -1,7 +0,0 @@
-Metadata-Version: 2.1
-Name: robobin
-Version: 0.0.0
-Summary: TODO: Package description
-Maintainer: paulw
-Maintainer-email: plw1g21@soton.ac.uk
-License: TODO: License declaration
diff --git a/ros2/build/robobin/robobin.egg-info/SOURCES.txt b/ros2/build/robobin/robobin.egg-info/SOURCES.txt
deleted file mode 100644
index 87703c5e30f54cd56d77173264cf63cfa42db567..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/robobin.egg-info/SOURCES.txt
+++ /dev/null
@@ -1,22 +0,0 @@
-package.xml
-setup.cfg
-setup.py
-../../build/robobin/robobin.egg-info/PKG-INFO
-../../build/robobin/robobin.egg-info/SOURCES.txt
-../../build/robobin/robobin.egg-info/dependency_links.txt
-../../build/robobin/robobin.egg-info/entry_points.txt
-../../build/robobin/robobin.egg-info/requires.txt
-../../build/robobin/robobin.egg-info/top_level.txt
-../../build/robobin/robobin.egg-info/zip-safe
-launch/robobin_launch.py
-resource/robobin
-robobin/__init__.py
-robobin/api_node.py
-robobin/motor_control_node.py
-robobin/uwb_navigation_node.py
-robobin/helpers/__init__.py
-robobin/helpers/connection_manager.py
-robobin/helpers/message_handler.py
-test/test_copyright.py
-test/test_flake8.py
-test/test_pep257.py
\ No newline at end of file
diff --git a/ros2/build/robobin/robobin.egg-info/dependency_links.txt b/ros2/build/robobin/robobin.egg-info/dependency_links.txt
deleted file mode 100644
index 8b137891791fe96927ad78e64b0aad7bded08bdc..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/robobin.egg-info/dependency_links.txt
+++ /dev/null
@@ -1 +0,0 @@
-
diff --git a/ros2/build/robobin/robobin.egg-info/entry_points.txt b/ros2/build/robobin/robobin.egg-info/entry_points.txt
deleted file mode 100644
index a569c6445838df1de986e4c1140c21af9733dc9c..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/robobin.egg-info/entry_points.txt
+++ /dev/null
@@ -1,4 +0,0 @@
-[console_scripts]
-api_node = robobin.api_node:main
-motor_control_node = robobin.motor_control_node:main
-uwb_navigation_node = robobin.uwb_navigation_node:main
diff --git a/ros2/build/robobin/robobin.egg-info/requires.txt b/ros2/build/robobin/robobin.egg-info/requires.txt
deleted file mode 100644
index 49fe098d9e6bccd89482b34510da60ab28556880..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/robobin.egg-info/requires.txt
+++ /dev/null
@@ -1 +0,0 @@
-setuptools
diff --git a/ros2/build/robobin/robobin.egg-info/top_level.txt b/ros2/build/robobin/robobin.egg-info/top_level.txt
deleted file mode 100644
index 2ca7c929754f574fe60649fed5f1333479af4ef7..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/robobin.egg-info/top_level.txt
+++ /dev/null
@@ -1 +0,0 @@
-robobin
diff --git a/ros2/build/robobin/robobin.egg-info/zip-safe b/ros2/build/robobin/robobin.egg-info/zip-safe
deleted file mode 100644
index 8b137891791fe96927ad78e64b0aad7bded08bdc..0000000000000000000000000000000000000000
--- a/ros2/build/robobin/robobin.egg-info/zip-safe
+++ /dev/null
@@ -1 +0,0 @@
-
diff --git a/ros2/install/.colcon_install_layout b/ros2/install/.colcon_install_layout
deleted file mode 100644
index 3aad5336af1f22b8088508218dceeda3d7bc8cc2..0000000000000000000000000000000000000000
--- a/ros2/install/.colcon_install_layout
+++ /dev/null
@@ -1 +0,0 @@
-isolated
diff --git a/ros2/install/COLCON_IGNORE b/ros2/install/COLCON_IGNORE
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/install/_local_setup_util_ps1.py b/ros2/install/_local_setup_util_ps1.py
deleted file mode 100644
index 3c6d9e8779050f742ec78af8a4d55abc4de7841b..0000000000000000000000000000000000000000
--- a/ros2/install/_local_setup_util_ps1.py
+++ /dev/null
@@ -1,407 +0,0 @@
-# Copyright 2016-2019 Dirk Thomas
-# Licensed under the Apache License, Version 2.0
-
-import argparse
-from collections import OrderedDict
-import os
-from pathlib import Path
-import sys
-
-
-FORMAT_STR_COMMENT_LINE = '# {comment}'
-FORMAT_STR_SET_ENV_VAR = 'Set-Item -Path "Env:{name}" -Value "{value}"'
-FORMAT_STR_USE_ENV_VAR = '$env:{name}'
-FORMAT_STR_INVOKE_SCRIPT = '_colcon_prefix_powershell_source_script "{script_path}"'  # noqa: E501
-FORMAT_STR_REMOVE_LEADING_SEPARATOR = ''  # noqa: E501
-FORMAT_STR_REMOVE_TRAILING_SEPARATOR = ''  # noqa: E501
-
-DSV_TYPE_APPEND_NON_DUPLICATE = 'append-non-duplicate'
-DSV_TYPE_PREPEND_NON_DUPLICATE = 'prepend-non-duplicate'
-DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS = 'prepend-non-duplicate-if-exists'
-DSV_TYPE_SET = 'set'
-DSV_TYPE_SET_IF_UNSET = 'set-if-unset'
-DSV_TYPE_SOURCE = 'source'
-
-
-def main(argv=sys.argv[1:]):  # noqa: D103
-    parser = argparse.ArgumentParser(
-        description='Output shell commands for the packages in topological '
-                    'order')
-    parser.add_argument(
-        'primary_extension',
-        help='The file extension of the primary shell')
-    parser.add_argument(
-        'additional_extension', nargs='?',
-        help='The additional file extension to be considered')
-    parser.add_argument(
-        '--merged-install', action='store_true',
-        help='All install prefixes are merged into a single location')
-    args = parser.parse_args(argv)
-
-    packages = get_packages(Path(__file__).parent, args.merged_install)
-
-    ordered_packages = order_packages(packages)
-    for pkg_name in ordered_packages:
-        if _include_comments():
-            print(
-                FORMAT_STR_COMMENT_LINE.format_map(
-                    {'comment': 'Package: ' + pkg_name}))
-        prefix = os.path.abspath(os.path.dirname(__file__))
-        if not args.merged_install:
-            prefix = os.path.join(prefix, pkg_name)
-        for line in get_commands(
-            pkg_name, prefix, args.primary_extension,
-            args.additional_extension
-        ):
-            print(line)
-
-    for line in _remove_ending_separators():
-        print(line)
-
-
-def get_packages(prefix_path, merged_install):
-    """
-    Find packages based on colcon-specific files created during installation.
-
-    :param Path prefix_path: The install prefix path of all packages
-    :param bool merged_install: The flag if the packages are all installed
-      directly in the prefix or if each package is installed in a subdirectory
-      named after the package
-    :returns: A mapping from the package name to the set of runtime
-      dependencies
-    :rtype: dict
-    """
-    packages = {}
-    # since importing colcon_core isn't feasible here the following constant
-    # must match colcon_core.location.get_relative_package_index_path()
-    subdirectory = 'share/colcon-core/packages'
-    if merged_install:
-        # return if workspace is empty
-        if not (prefix_path / subdirectory).is_dir():
-            return packages
-        # find all files in the subdirectory
-        for p in (prefix_path / subdirectory).iterdir():
-            if not p.is_file():
-                continue
-            if p.name.startswith('.'):
-                continue
-            add_package_runtime_dependencies(p, packages)
-    else:
-        # for each subdirectory look for the package specific file
-        for p in prefix_path.iterdir():
-            if not p.is_dir():
-                continue
-            if p.name.startswith('.'):
-                continue
-            p = p / subdirectory / p.name
-            if p.is_file():
-                add_package_runtime_dependencies(p, packages)
-
-    # remove unknown dependencies
-    pkg_names = set(packages.keys())
-    for k in packages.keys():
-        packages[k] = {d for d in packages[k] if d in pkg_names}
-
-    return packages
-
-
-def add_package_runtime_dependencies(path, packages):
-    """
-    Check the path and if it exists extract the packages runtime dependencies.
-
-    :param Path path: The resource file containing the runtime dependencies
-    :param dict packages: A mapping from package names to the sets of runtime
-      dependencies to add to
-    """
-    content = path.read_text()
-    dependencies = set(content.split(os.pathsep) if content else [])
-    packages[path.name] = dependencies
-
-
-def order_packages(packages):
-    """
-    Order packages topologically.
-
-    :param dict packages: A mapping from package name to the set of runtime
-      dependencies
-    :returns: The package names
-    :rtype: list
-    """
-    # select packages with no dependencies in alphabetical order
-    to_be_ordered = list(packages.keys())
-    ordered = []
-    while to_be_ordered:
-        pkg_names_without_deps = [
-            name for name in to_be_ordered if not packages[name]]
-        if not pkg_names_without_deps:
-            reduce_cycle_set(packages)
-            raise RuntimeError(
-                'Circular dependency between: ' + ', '.join(sorted(packages)))
-        pkg_names_without_deps.sort()
-        pkg_name = pkg_names_without_deps[0]
-        to_be_ordered.remove(pkg_name)
-        ordered.append(pkg_name)
-        # remove item from dependency lists
-        for k in list(packages.keys()):
-            if pkg_name in packages[k]:
-                packages[k].remove(pkg_name)
-    return ordered
-
-
-def reduce_cycle_set(packages):
-    """
-    Reduce the set of packages to the ones part of the circular dependency.
-
-    :param dict packages: A mapping from package name to the set of runtime
-      dependencies which is modified in place
-    """
-    last_depended = None
-    while len(packages) > 0:
-        # get all remaining dependencies
-        depended = set()
-        for pkg_name, dependencies in packages.items():
-            depended = depended.union(dependencies)
-        # remove all packages which are not dependent on
-        for name in list(packages.keys()):
-            if name not in depended:
-                del packages[name]
-        if last_depended:
-            # if remaining packages haven't changed return them
-            if last_depended == depended:
-                return packages.keys()
-        # otherwise reduce again
-        last_depended = depended
-
-
-def _include_comments():
-    # skipping comment lines when COLCON_TRACE is not set speeds up the
-    # processing especially on Windows
-    return bool(os.environ.get('COLCON_TRACE'))
-
-
-def get_commands(pkg_name, prefix, primary_extension, additional_extension):
-    commands = []
-    package_dsv_path = os.path.join(prefix, 'share', pkg_name, 'package.dsv')
-    if os.path.exists(package_dsv_path):
-        commands += process_dsv_file(
-            package_dsv_path, prefix, primary_extension, additional_extension)
-    return commands
-
-
-def process_dsv_file(
-    dsv_path, prefix, primary_extension=None, additional_extension=None
-):
-    commands = []
-    if _include_comments():
-        commands.append(FORMAT_STR_COMMENT_LINE.format_map({'comment': dsv_path}))
-    with open(dsv_path, 'r') as h:
-        content = h.read()
-    lines = content.splitlines()
-
-    basenames = OrderedDict()
-    for i, line in enumerate(lines):
-        # skip over empty or whitespace-only lines
-        if not line.strip():
-            continue
-        # skip over comments
-        if line.startswith('#'):
-            continue
-        try:
-            type_, remainder = line.split(';', 1)
-        except ValueError:
-            raise RuntimeError(
-                "Line %d in '%s' doesn't contain a semicolon separating the "
-                'type from the arguments' % (i + 1, dsv_path))
-        if type_ != DSV_TYPE_SOURCE:
-            # handle non-source lines
-            try:
-                commands += handle_dsv_types_except_source(
-                    type_, remainder, prefix)
-            except RuntimeError as e:
-                raise RuntimeError(
-                    "Line %d in '%s' %s" % (i + 1, dsv_path, e)) from e
-        else:
-            # group remaining source lines by basename
-            path_without_ext, ext = os.path.splitext(remainder)
-            if path_without_ext not in basenames:
-                basenames[path_without_ext] = set()
-            assert ext.startswith('.')
-            ext = ext[1:]
-            if ext in (primary_extension, additional_extension):
-                basenames[path_without_ext].add(ext)
-
-    # add the dsv extension to each basename if the file exists
-    for basename, extensions in basenames.items():
-        if not os.path.isabs(basename):
-            basename = os.path.join(prefix, basename)
-        if os.path.exists(basename + '.dsv'):
-            extensions.add('dsv')
-
-    for basename, extensions in basenames.items():
-        if not os.path.isabs(basename):
-            basename = os.path.join(prefix, basename)
-        if 'dsv' in extensions:
-            # process dsv files recursively
-            commands += process_dsv_file(
-                basename + '.dsv', prefix, primary_extension=primary_extension,
-                additional_extension=additional_extension)
-        elif primary_extension in extensions and len(extensions) == 1:
-            # source primary-only files
-            commands += [
-                FORMAT_STR_INVOKE_SCRIPT.format_map({
-                    'prefix': prefix,
-                    'script_path': basename + '.' + primary_extension})]
-        elif additional_extension in extensions:
-            # source non-primary files
-            commands += [
-                FORMAT_STR_INVOKE_SCRIPT.format_map({
-                    'prefix': prefix,
-                    'script_path': basename + '.' + additional_extension})]
-
-    return commands
-
-
-def handle_dsv_types_except_source(type_, remainder, prefix):
-    commands = []
-    if type_ in (DSV_TYPE_SET, DSV_TYPE_SET_IF_UNSET):
-        try:
-            env_name, value = remainder.split(';', 1)
-        except ValueError:
-            raise RuntimeError(
-                "doesn't contain a semicolon separating the environment name "
-                'from the value')
-        try_prefixed_value = os.path.join(prefix, value) if value else prefix
-        if os.path.exists(try_prefixed_value):
-            value = try_prefixed_value
-        if type_ == DSV_TYPE_SET:
-            commands += _set(env_name, value)
-        elif type_ == DSV_TYPE_SET_IF_UNSET:
-            commands += _set_if_unset(env_name, value)
-        else:
-            assert False
-    elif type_ in (
-        DSV_TYPE_APPEND_NON_DUPLICATE,
-        DSV_TYPE_PREPEND_NON_DUPLICATE,
-        DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS
-    ):
-        try:
-            env_name_and_values = remainder.split(';')
-        except ValueError:
-            raise RuntimeError(
-                "doesn't contain a semicolon separating the environment name "
-                'from the values')
-        env_name = env_name_and_values[0]
-        values = env_name_and_values[1:]
-        for value in values:
-            if not value:
-                value = prefix
-            elif not os.path.isabs(value):
-                value = os.path.join(prefix, value)
-            if (
-                type_ == DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS and
-                not os.path.exists(value)
-            ):
-                comment = f'skip extending {env_name} with not existing ' \
-                    f'path: {value}'
-                if _include_comments():
-                    commands.append(
-                        FORMAT_STR_COMMENT_LINE.format_map({'comment': comment}))
-            elif type_ == DSV_TYPE_APPEND_NON_DUPLICATE:
-                commands += _append_unique_value(env_name, value)
-            else:
-                commands += _prepend_unique_value(env_name, value)
-    else:
-        raise RuntimeError(
-            'contains an unknown environment hook type: ' + type_)
-    return commands
-
-
-env_state = {}
-
-
-def _append_unique_value(name, value):
-    global env_state
-    if name not in env_state:
-        if os.environ.get(name):
-            env_state[name] = set(os.environ[name].split(os.pathsep))
-        else:
-            env_state[name] = set()
-    # append even if the variable has not been set yet, in case a shell script sets the
-    # same variable without the knowledge of this Python script.
-    # later _remove_ending_separators() will cleanup any unintentional leading separator
-    extend = FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + os.pathsep
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': extend + value})
-    if value not in env_state[name]:
-        env_state[name].add(value)
-    else:
-        if not _include_comments():
-            return []
-        line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
-    return [line]
-
-
-def _prepend_unique_value(name, value):
-    global env_state
-    if name not in env_state:
-        if os.environ.get(name):
-            env_state[name] = set(os.environ[name].split(os.pathsep))
-        else:
-            env_state[name] = set()
-    # prepend even if the variable has not been set yet, in case a shell script sets the
-    # same variable without the knowledge of this Python script.
-    # later _remove_ending_separators() will cleanup any unintentional trailing separator
-    extend = os.pathsep + FORMAT_STR_USE_ENV_VAR.format_map({'name': name})
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': value + extend})
-    if value not in env_state[name]:
-        env_state[name].add(value)
-    else:
-        if not _include_comments():
-            return []
-        line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
-    return [line]
-
-
-# generate commands for removing prepended underscores
-def _remove_ending_separators():
-    # do nothing if the shell extension does not implement the logic
-    if FORMAT_STR_REMOVE_TRAILING_SEPARATOR is None:
-        return []
-
-    global env_state
-    commands = []
-    for name in env_state:
-        # skip variables that already had values before this script started prepending
-        if name in os.environ:
-            continue
-        commands += [
-            FORMAT_STR_REMOVE_LEADING_SEPARATOR.format_map({'name': name}),
-            FORMAT_STR_REMOVE_TRAILING_SEPARATOR.format_map({'name': name})]
-    return commands
-
-
-def _set(name, value):
-    global env_state
-    env_state[name] = value
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': value})
-    return [line]
-
-
-def _set_if_unset(name, value):
-    global env_state
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': value})
-    if env_state.get(name, os.environ.get(name)):
-        line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
-    return [line]
-
-
-if __name__ == '__main__':  # pragma: no cover
-    try:
-        rc = main()
-    except RuntimeError as e:
-        print(str(e), file=sys.stderr)
-        rc = 1
-    sys.exit(rc)
diff --git a/ros2/install/_local_setup_util_sh.py b/ros2/install/_local_setup_util_sh.py
deleted file mode 100644
index f67eaa9891ec587c4bbe364da6b18b5c65631f4d..0000000000000000000000000000000000000000
--- a/ros2/install/_local_setup_util_sh.py
+++ /dev/null
@@ -1,407 +0,0 @@
-# Copyright 2016-2019 Dirk Thomas
-# Licensed under the Apache License, Version 2.0
-
-import argparse
-from collections import OrderedDict
-import os
-from pathlib import Path
-import sys
-
-
-FORMAT_STR_COMMENT_LINE = '# {comment}'
-FORMAT_STR_SET_ENV_VAR = 'export {name}="{value}"'
-FORMAT_STR_USE_ENV_VAR = '${name}'
-FORMAT_STR_INVOKE_SCRIPT = 'COLCON_CURRENT_PREFIX="{prefix}" _colcon_prefix_sh_source_script "{script_path}"'  # noqa: E501
-FORMAT_STR_REMOVE_LEADING_SEPARATOR = 'if [ "$(echo -n ${name} | head -c 1)" = ":" ]; then export {name}=${{{name}#?}} ; fi'  # noqa: E501
-FORMAT_STR_REMOVE_TRAILING_SEPARATOR = 'if [ "$(echo -n ${name} | tail -c 1)" = ":" ]; then export {name}=${{{name}%?}} ; fi'  # noqa: E501
-
-DSV_TYPE_APPEND_NON_DUPLICATE = 'append-non-duplicate'
-DSV_TYPE_PREPEND_NON_DUPLICATE = 'prepend-non-duplicate'
-DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS = 'prepend-non-duplicate-if-exists'
-DSV_TYPE_SET = 'set'
-DSV_TYPE_SET_IF_UNSET = 'set-if-unset'
-DSV_TYPE_SOURCE = 'source'
-
-
-def main(argv=sys.argv[1:]):  # noqa: D103
-    parser = argparse.ArgumentParser(
-        description='Output shell commands for the packages in topological '
-                    'order')
-    parser.add_argument(
-        'primary_extension',
-        help='The file extension of the primary shell')
-    parser.add_argument(
-        'additional_extension', nargs='?',
-        help='The additional file extension to be considered')
-    parser.add_argument(
-        '--merged-install', action='store_true',
-        help='All install prefixes are merged into a single location')
-    args = parser.parse_args(argv)
-
-    packages = get_packages(Path(__file__).parent, args.merged_install)
-
-    ordered_packages = order_packages(packages)
-    for pkg_name in ordered_packages:
-        if _include_comments():
-            print(
-                FORMAT_STR_COMMENT_LINE.format_map(
-                    {'comment': 'Package: ' + pkg_name}))
-        prefix = os.path.abspath(os.path.dirname(__file__))
-        if not args.merged_install:
-            prefix = os.path.join(prefix, pkg_name)
-        for line in get_commands(
-            pkg_name, prefix, args.primary_extension,
-            args.additional_extension
-        ):
-            print(line)
-
-    for line in _remove_ending_separators():
-        print(line)
-
-
-def get_packages(prefix_path, merged_install):
-    """
-    Find packages based on colcon-specific files created during installation.
-
-    :param Path prefix_path: The install prefix path of all packages
-    :param bool merged_install: The flag if the packages are all installed
-      directly in the prefix or if each package is installed in a subdirectory
-      named after the package
-    :returns: A mapping from the package name to the set of runtime
-      dependencies
-    :rtype: dict
-    """
-    packages = {}
-    # since importing colcon_core isn't feasible here the following constant
-    # must match colcon_core.location.get_relative_package_index_path()
-    subdirectory = 'share/colcon-core/packages'
-    if merged_install:
-        # return if workspace is empty
-        if not (prefix_path / subdirectory).is_dir():
-            return packages
-        # find all files in the subdirectory
-        for p in (prefix_path / subdirectory).iterdir():
-            if not p.is_file():
-                continue
-            if p.name.startswith('.'):
-                continue
-            add_package_runtime_dependencies(p, packages)
-    else:
-        # for each subdirectory look for the package specific file
-        for p in prefix_path.iterdir():
-            if not p.is_dir():
-                continue
-            if p.name.startswith('.'):
-                continue
-            p = p / subdirectory / p.name
-            if p.is_file():
-                add_package_runtime_dependencies(p, packages)
-
-    # remove unknown dependencies
-    pkg_names = set(packages.keys())
-    for k in packages.keys():
-        packages[k] = {d for d in packages[k] if d in pkg_names}
-
-    return packages
-
-
-def add_package_runtime_dependencies(path, packages):
-    """
-    Check the path and if it exists extract the packages runtime dependencies.
-
-    :param Path path: The resource file containing the runtime dependencies
-    :param dict packages: A mapping from package names to the sets of runtime
-      dependencies to add to
-    """
-    content = path.read_text()
-    dependencies = set(content.split(os.pathsep) if content else [])
-    packages[path.name] = dependencies
-
-
-def order_packages(packages):
-    """
-    Order packages topologically.
-
-    :param dict packages: A mapping from package name to the set of runtime
-      dependencies
-    :returns: The package names
-    :rtype: list
-    """
-    # select packages with no dependencies in alphabetical order
-    to_be_ordered = list(packages.keys())
-    ordered = []
-    while to_be_ordered:
-        pkg_names_without_deps = [
-            name for name in to_be_ordered if not packages[name]]
-        if not pkg_names_without_deps:
-            reduce_cycle_set(packages)
-            raise RuntimeError(
-                'Circular dependency between: ' + ', '.join(sorted(packages)))
-        pkg_names_without_deps.sort()
-        pkg_name = pkg_names_without_deps[0]
-        to_be_ordered.remove(pkg_name)
-        ordered.append(pkg_name)
-        # remove item from dependency lists
-        for k in list(packages.keys()):
-            if pkg_name in packages[k]:
-                packages[k].remove(pkg_name)
-    return ordered
-
-
-def reduce_cycle_set(packages):
-    """
-    Reduce the set of packages to the ones part of the circular dependency.
-
-    :param dict packages: A mapping from package name to the set of runtime
-      dependencies which is modified in place
-    """
-    last_depended = None
-    while len(packages) > 0:
-        # get all remaining dependencies
-        depended = set()
-        for pkg_name, dependencies in packages.items():
-            depended = depended.union(dependencies)
-        # remove all packages which are not dependent on
-        for name in list(packages.keys()):
-            if name not in depended:
-                del packages[name]
-        if last_depended:
-            # if remaining packages haven't changed return them
-            if last_depended == depended:
-                return packages.keys()
-        # otherwise reduce again
-        last_depended = depended
-
-
-def _include_comments():
-    # skipping comment lines when COLCON_TRACE is not set speeds up the
-    # processing especially on Windows
-    return bool(os.environ.get('COLCON_TRACE'))
-
-
-def get_commands(pkg_name, prefix, primary_extension, additional_extension):
-    commands = []
-    package_dsv_path = os.path.join(prefix, 'share', pkg_name, 'package.dsv')
-    if os.path.exists(package_dsv_path):
-        commands += process_dsv_file(
-            package_dsv_path, prefix, primary_extension, additional_extension)
-    return commands
-
-
-def process_dsv_file(
-    dsv_path, prefix, primary_extension=None, additional_extension=None
-):
-    commands = []
-    if _include_comments():
-        commands.append(FORMAT_STR_COMMENT_LINE.format_map({'comment': dsv_path}))
-    with open(dsv_path, 'r') as h:
-        content = h.read()
-    lines = content.splitlines()
-
-    basenames = OrderedDict()
-    for i, line in enumerate(lines):
-        # skip over empty or whitespace-only lines
-        if not line.strip():
-            continue
-        # skip over comments
-        if line.startswith('#'):
-            continue
-        try:
-            type_, remainder = line.split(';', 1)
-        except ValueError:
-            raise RuntimeError(
-                "Line %d in '%s' doesn't contain a semicolon separating the "
-                'type from the arguments' % (i + 1, dsv_path))
-        if type_ != DSV_TYPE_SOURCE:
-            # handle non-source lines
-            try:
-                commands += handle_dsv_types_except_source(
-                    type_, remainder, prefix)
-            except RuntimeError as e:
-                raise RuntimeError(
-                    "Line %d in '%s' %s" % (i + 1, dsv_path, e)) from e
-        else:
-            # group remaining source lines by basename
-            path_without_ext, ext = os.path.splitext(remainder)
-            if path_without_ext not in basenames:
-                basenames[path_without_ext] = set()
-            assert ext.startswith('.')
-            ext = ext[1:]
-            if ext in (primary_extension, additional_extension):
-                basenames[path_without_ext].add(ext)
-
-    # add the dsv extension to each basename if the file exists
-    for basename, extensions in basenames.items():
-        if not os.path.isabs(basename):
-            basename = os.path.join(prefix, basename)
-        if os.path.exists(basename + '.dsv'):
-            extensions.add('dsv')
-
-    for basename, extensions in basenames.items():
-        if not os.path.isabs(basename):
-            basename = os.path.join(prefix, basename)
-        if 'dsv' in extensions:
-            # process dsv files recursively
-            commands += process_dsv_file(
-                basename + '.dsv', prefix, primary_extension=primary_extension,
-                additional_extension=additional_extension)
-        elif primary_extension in extensions and len(extensions) == 1:
-            # source primary-only files
-            commands += [
-                FORMAT_STR_INVOKE_SCRIPT.format_map({
-                    'prefix': prefix,
-                    'script_path': basename + '.' + primary_extension})]
-        elif additional_extension in extensions:
-            # source non-primary files
-            commands += [
-                FORMAT_STR_INVOKE_SCRIPT.format_map({
-                    'prefix': prefix,
-                    'script_path': basename + '.' + additional_extension})]
-
-    return commands
-
-
-def handle_dsv_types_except_source(type_, remainder, prefix):
-    commands = []
-    if type_ in (DSV_TYPE_SET, DSV_TYPE_SET_IF_UNSET):
-        try:
-            env_name, value = remainder.split(';', 1)
-        except ValueError:
-            raise RuntimeError(
-                "doesn't contain a semicolon separating the environment name "
-                'from the value')
-        try_prefixed_value = os.path.join(prefix, value) if value else prefix
-        if os.path.exists(try_prefixed_value):
-            value = try_prefixed_value
-        if type_ == DSV_TYPE_SET:
-            commands += _set(env_name, value)
-        elif type_ == DSV_TYPE_SET_IF_UNSET:
-            commands += _set_if_unset(env_name, value)
-        else:
-            assert False
-    elif type_ in (
-        DSV_TYPE_APPEND_NON_DUPLICATE,
-        DSV_TYPE_PREPEND_NON_DUPLICATE,
-        DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS
-    ):
-        try:
-            env_name_and_values = remainder.split(';')
-        except ValueError:
-            raise RuntimeError(
-                "doesn't contain a semicolon separating the environment name "
-                'from the values')
-        env_name = env_name_and_values[0]
-        values = env_name_and_values[1:]
-        for value in values:
-            if not value:
-                value = prefix
-            elif not os.path.isabs(value):
-                value = os.path.join(prefix, value)
-            if (
-                type_ == DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS and
-                not os.path.exists(value)
-            ):
-                comment = f'skip extending {env_name} with not existing ' \
-                    f'path: {value}'
-                if _include_comments():
-                    commands.append(
-                        FORMAT_STR_COMMENT_LINE.format_map({'comment': comment}))
-            elif type_ == DSV_TYPE_APPEND_NON_DUPLICATE:
-                commands += _append_unique_value(env_name, value)
-            else:
-                commands += _prepend_unique_value(env_name, value)
-    else:
-        raise RuntimeError(
-            'contains an unknown environment hook type: ' + type_)
-    return commands
-
-
-env_state = {}
-
-
-def _append_unique_value(name, value):
-    global env_state
-    if name not in env_state:
-        if os.environ.get(name):
-            env_state[name] = set(os.environ[name].split(os.pathsep))
-        else:
-            env_state[name] = set()
-    # append even if the variable has not been set yet, in case a shell script sets the
-    # same variable without the knowledge of this Python script.
-    # later _remove_ending_separators() will cleanup any unintentional leading separator
-    extend = FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + os.pathsep
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': extend + value})
-    if value not in env_state[name]:
-        env_state[name].add(value)
-    else:
-        if not _include_comments():
-            return []
-        line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
-    return [line]
-
-
-def _prepend_unique_value(name, value):
-    global env_state
-    if name not in env_state:
-        if os.environ.get(name):
-            env_state[name] = set(os.environ[name].split(os.pathsep))
-        else:
-            env_state[name] = set()
-    # prepend even if the variable has not been set yet, in case a shell script sets the
-    # same variable without the knowledge of this Python script.
-    # later _remove_ending_separators() will cleanup any unintentional trailing separator
-    extend = os.pathsep + FORMAT_STR_USE_ENV_VAR.format_map({'name': name})
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': value + extend})
-    if value not in env_state[name]:
-        env_state[name].add(value)
-    else:
-        if not _include_comments():
-            return []
-        line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
-    return [line]
-
-
-# generate commands for removing prepended underscores
-def _remove_ending_separators():
-    # do nothing if the shell extension does not implement the logic
-    if FORMAT_STR_REMOVE_TRAILING_SEPARATOR is None:
-        return []
-
-    global env_state
-    commands = []
-    for name in env_state:
-        # skip variables that already had values before this script started prepending
-        if name in os.environ:
-            continue
-        commands += [
-            FORMAT_STR_REMOVE_LEADING_SEPARATOR.format_map({'name': name}),
-            FORMAT_STR_REMOVE_TRAILING_SEPARATOR.format_map({'name': name})]
-    return commands
-
-
-def _set(name, value):
-    global env_state
-    env_state[name] = value
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': value})
-    return [line]
-
-
-def _set_if_unset(name, value):
-    global env_state
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': value})
-    if env_state.get(name, os.environ.get(name)):
-        line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
-    return [line]
-
-
-if __name__ == '__main__':  # pragma: no cover
-    try:
-        rc = main()
-    except RuntimeError as e:
-        print(str(e), file=sys.stderr)
-        rc = 1
-    sys.exit(rc)
diff --git a/ros2/install/local_setup.bash b/ros2/install/local_setup.bash
deleted file mode 100644
index 03f00256c1a126057ca924bdd48ec74444b0cc10..0000000000000000000000000000000000000000
--- a/ros2/install/local_setup.bash
+++ /dev/null
@@ -1,121 +0,0 @@
-# generated from colcon_bash/shell/template/prefix.bash.em
-
-# This script extends the environment with all packages contained in this
-# prefix path.
-
-# a bash script is able to determine its own path if necessary
-if [ -z "$COLCON_CURRENT_PREFIX" ]; then
-  _colcon_prefix_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)"
-else
-  _colcon_prefix_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
-fi
-
-# function to prepend a value to a variable
-# which uses colons as separators
-# duplicates as well as trailing separators are avoided
-# first argument: the name of the result variable
-# second argument: the value to be prepended
-_colcon_prefix_bash_prepend_unique_value() {
-  # arguments
-  _listname="$1"
-  _value="$2"
-
-  # get values from variable
-  eval _values=\"\$$_listname\"
-  # backup the field separator
-  _colcon_prefix_bash_prepend_unique_value_IFS="$IFS"
-  IFS=":"
-  # start with the new value
-  _all_values="$_value"
-  _contained_value=""
-  # iterate over existing values in the variable
-  for _item in $_values; do
-    # ignore empty strings
-    if [ -z "$_item" ]; then
-      continue
-    fi
-    # ignore duplicates of _value
-    if [ "$_item" = "$_value" ]; then
-      _contained_value=1
-      continue
-    fi
-    # keep non-duplicate values
-    _all_values="$_all_values:$_item"
-  done
-  unset _item
-  if [ -z "$_contained_value" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      if [ "$_all_values" = "$_value" ]; then
-        echo "export $_listname=$_value"
-      else
-        echo "export $_listname=$_value:\$$_listname"
-      fi
-    fi
-  fi
-  unset _contained_value
-  # restore the field separator
-  IFS="$_colcon_prefix_bash_prepend_unique_value_IFS"
-  unset _colcon_prefix_bash_prepend_unique_value_IFS
-  # export the updated variable
-  eval export $_listname=\"$_all_values\"
-  unset _all_values
-  unset _values
-
-  unset _value
-  unset _listname
-}
-
-# add this prefix to the COLCON_PREFIX_PATH
-_colcon_prefix_bash_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_bash_COLCON_CURRENT_PREFIX"
-unset _colcon_prefix_bash_prepend_unique_value
-
-# check environment variable for custom Python executable
-if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then
-  if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then
-    echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist"
-    return 1
-  fi
-  _colcon_python_executable="$COLCON_PYTHON_EXECUTABLE"
-else
-  # try the Python executable known at configure time
-  _colcon_python_executable="/usr/bin/python3"
-  # if it doesn't exist try a fall back
-  if [ ! -f "$_colcon_python_executable" ]; then
-    if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then
-      echo "error: unable to find python3 executable"
-      return 1
-    fi
-    _colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"`
-  fi
-fi
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-_colcon_prefix_sh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$1"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# get all commands in topological order
-_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_bash_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh bash)"
-unset _colcon_python_executable
-if [ -n "$COLCON_TRACE" ]; then
-  echo "$(declare -f _colcon_prefix_sh_source_script)"
-  echo "# Execute generated script:"
-  echo "# <<<"
-  echo "${_colcon_ordered_commands}"
-  echo "# >>>"
-  echo "unset _colcon_prefix_sh_source_script"
-fi
-eval "${_colcon_ordered_commands}"
-unset _colcon_ordered_commands
-
-unset _colcon_prefix_sh_source_script
-
-unset _colcon_prefix_bash_COLCON_CURRENT_PREFIX
diff --git a/ros2/install/local_setup.ps1 b/ros2/install/local_setup.ps1
deleted file mode 100644
index 6f68c8dede9ed4ecb63a4eb6ac2a7450bd18ec3b..0000000000000000000000000000000000000000
--- a/ros2/install/local_setup.ps1
+++ /dev/null
@@ -1,55 +0,0 @@
-# generated from colcon_powershell/shell/template/prefix.ps1.em
-
-# This script extends the environment with all packages contained in this
-# prefix path.
-
-# check environment variable for custom Python executable
-if ($env:COLCON_PYTHON_EXECUTABLE) {
-  if (!(Test-Path "$env:COLCON_PYTHON_EXECUTABLE" -PathType Leaf)) {
-    echo "error: COLCON_PYTHON_EXECUTABLE '$env:COLCON_PYTHON_EXECUTABLE' doesn't exist"
-    exit 1
-  }
-  $_colcon_python_executable="$env:COLCON_PYTHON_EXECUTABLE"
-} else {
-  # use the Python executable known at configure time
-  $_colcon_python_executable="/usr/bin/python3"
-  # if it doesn't exist try a fall back
-  if (!(Test-Path "$_colcon_python_executable" -PathType Leaf)) {
-    if (!(Get-Command "python3" -ErrorAction SilentlyContinue)) {
-      echo "error: unable to find python3 executable"
-      exit 1
-    }
-    $_colcon_python_executable="python3"
-  }
-}
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-function _colcon_prefix_powershell_source_script {
-  param (
-    $_colcon_prefix_powershell_source_script_param
-  )
-  # source script with conditional trace output
-  if (Test-Path $_colcon_prefix_powershell_source_script_param) {
-    if ($env:COLCON_TRACE) {
-      echo ". '$_colcon_prefix_powershell_source_script_param'"
-    }
-    . "$_colcon_prefix_powershell_source_script_param"
-  } else {
-    Write-Error "not found: '$_colcon_prefix_powershell_source_script_param'"
-  }
-}
-
-# get all commands in topological order
-$_colcon_ordered_commands = & "$_colcon_python_executable" "$(Split-Path $PSCommandPath -Parent)/_local_setup_util_ps1.py" ps1
-
-# execute all commands in topological order
-if ($env:COLCON_TRACE) {
-  echo "Execute generated script:"
-  echo "<<<"
-  $_colcon_ordered_commands.Split([Environment]::NewLine, [StringSplitOptions]::RemoveEmptyEntries) | Write-Output
-  echo ">>>"
-}
-if ($_colcon_ordered_commands) {
-  $_colcon_ordered_commands.Split([Environment]::NewLine, [StringSplitOptions]::RemoveEmptyEntries) | Invoke-Expression
-}
diff --git a/ros2/install/local_setup.sh b/ros2/install/local_setup.sh
deleted file mode 100644
index f1369171fde434086f55a9a47b87fdc68c1a25f0..0000000000000000000000000000000000000000
--- a/ros2/install/local_setup.sh
+++ /dev/null
@@ -1,137 +0,0 @@
-# generated from colcon_core/shell/template/prefix.sh.em
-
-# This script extends the environment with all packages contained in this
-# prefix path.
-
-# since a plain shell script can't determine its own path when being sourced
-# either use the provided COLCON_CURRENT_PREFIX
-# or fall back to the build time prefix (if it exists)
-_colcon_prefix_sh_COLCON_CURRENT_PREFIX="/home/robobin/robobin/ros2/install"
-if [ -z "$COLCON_CURRENT_PREFIX" ]; then
-  if [ ! -d "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX" ]; then
-    echo "The build time path \"$_colcon_prefix_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2
-    unset _colcon_prefix_sh_COLCON_CURRENT_PREFIX
-    return 1
-  fi
-else
-  _colcon_prefix_sh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
-fi
-
-# function to prepend a value to a variable
-# which uses colons as separators
-# duplicates as well as trailing separators are avoided
-# first argument: the name of the result variable
-# second argument: the value to be prepended
-_colcon_prefix_sh_prepend_unique_value() {
-  # arguments
-  _listname="$1"
-  _value="$2"
-
-  # get values from variable
-  eval _values=\"\$$_listname\"
-  # backup the field separator
-  _colcon_prefix_sh_prepend_unique_value_IFS="$IFS"
-  IFS=":"
-  # start with the new value
-  _all_values="$_value"
-  _contained_value=""
-  # iterate over existing values in the variable
-  for _item in $_values; do
-    # ignore empty strings
-    if [ -z "$_item" ]; then
-      continue
-    fi
-    # ignore duplicates of _value
-    if [ "$_item" = "$_value" ]; then
-      _contained_value=1
-      continue
-    fi
-    # keep non-duplicate values
-    _all_values="$_all_values:$_item"
-  done
-  unset _item
-  if [ -z "$_contained_value" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      if [ "$_all_values" = "$_value" ]; then
-        echo "export $_listname=$_value"
-      else
-        echo "export $_listname=$_value:\$$_listname"
-      fi
-    fi
-  fi
-  unset _contained_value
-  # restore the field separator
-  IFS="$_colcon_prefix_sh_prepend_unique_value_IFS"
-  unset _colcon_prefix_sh_prepend_unique_value_IFS
-  # export the updated variable
-  eval export $_listname=\"$_all_values\"
-  unset _all_values
-  unset _values
-
-  unset _value
-  unset _listname
-}
-
-# add this prefix to the COLCON_PREFIX_PATH
-_colcon_prefix_sh_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX"
-unset _colcon_prefix_sh_prepend_unique_value
-
-# check environment variable for custom Python executable
-if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then
-  if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then
-    echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist"
-    return 1
-  fi
-  _colcon_python_executable="$COLCON_PYTHON_EXECUTABLE"
-else
-  # try the Python executable known at configure time
-  _colcon_python_executable="/usr/bin/python3"
-  # if it doesn't exist try a fall back
-  if [ ! -f "$_colcon_python_executable" ]; then
-    if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then
-      echo "error: unable to find python3 executable"
-      return 1
-    fi
-    _colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"`
-  fi
-fi
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-_colcon_prefix_sh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$1"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# get all commands in topological order
-_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh)"
-unset _colcon_python_executable
-if [ -n "$COLCON_TRACE" ]; then
-  echo "_colcon_prefix_sh_source_script() {
-    if [ -f \"\$1\" ]; then
-      if [ -n \"\$COLCON_TRACE\" ]; then
-        echo \"# . \\\"\$1\\\"\"
-      fi
-      . \"\$1\"
-    else
-      echo \"not found: \\\"\$1\\\"\" 1>&2
-    fi
-  }"
-  echo "# Execute generated script:"
-  echo "# <<<"
-  echo "${_colcon_ordered_commands}"
-  echo "# >>>"
-  echo "unset _colcon_prefix_sh_source_script"
-fi
-eval "${_colcon_ordered_commands}"
-unset _colcon_ordered_commands
-
-unset _colcon_prefix_sh_source_script
-
-unset _colcon_prefix_sh_COLCON_CURRENT_PREFIX
diff --git a/ros2/install/local_setup.zsh b/ros2/install/local_setup.zsh
deleted file mode 100644
index b6487102f245a7b5ddb2b1da158d6b99ddc91d8b..0000000000000000000000000000000000000000
--- a/ros2/install/local_setup.zsh
+++ /dev/null
@@ -1,134 +0,0 @@
-# generated from colcon_zsh/shell/template/prefix.zsh.em
-
-# This script extends the environment with all packages contained in this
-# prefix path.
-
-# a zsh script is able to determine its own path if necessary
-if [ -z "$COLCON_CURRENT_PREFIX" ]; then
-  _colcon_prefix_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)"
-else
-  _colcon_prefix_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
-fi
-
-# function to convert array-like strings into arrays
-# to workaround SH_WORD_SPLIT not being set
-_colcon_prefix_zsh_convert_to_array() {
-  local _listname=$1
-  local _dollar="$"
-  local _split="{="
-  local _to_array="(\"$_dollar$_split$_listname}\")"
-  eval $_listname=$_to_array
-}
-
-# function to prepend a value to a variable
-# which uses colons as separators
-# duplicates as well as trailing separators are avoided
-# first argument: the name of the result variable
-# second argument: the value to be prepended
-_colcon_prefix_zsh_prepend_unique_value() {
-  # arguments
-  _listname="$1"
-  _value="$2"
-
-  # get values from variable
-  eval _values=\"\$$_listname\"
-  # backup the field separator
-  _colcon_prefix_zsh_prepend_unique_value_IFS="$IFS"
-  IFS=":"
-  # start with the new value
-  _all_values="$_value"
-  _contained_value=""
-  # workaround SH_WORD_SPLIT not being set
-  _colcon_prefix_zsh_convert_to_array _values
-  # iterate over existing values in the variable
-  for _item in $_values; do
-    # ignore empty strings
-    if [ -z "$_item" ]; then
-      continue
-    fi
-    # ignore duplicates of _value
-    if [ "$_item" = "$_value" ]; then
-      _contained_value=1
-      continue
-    fi
-    # keep non-duplicate values
-    _all_values="$_all_values:$_item"
-  done
-  unset _item
-  if [ -z "$_contained_value" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      if [ "$_all_values" = "$_value" ]; then
-        echo "export $_listname=$_value"
-      else
-        echo "export $_listname=$_value:\$$_listname"
-      fi
-    fi
-  fi
-  unset _contained_value
-  # restore the field separator
-  IFS="$_colcon_prefix_zsh_prepend_unique_value_IFS"
-  unset _colcon_prefix_zsh_prepend_unique_value_IFS
-  # export the updated variable
-  eval export $_listname=\"$_all_values\"
-  unset _all_values
-  unset _values
-
-  unset _value
-  unset _listname
-}
-
-# add this prefix to the COLCON_PREFIX_PATH
-_colcon_prefix_zsh_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_zsh_COLCON_CURRENT_PREFIX"
-unset _colcon_prefix_zsh_prepend_unique_value
-unset _colcon_prefix_zsh_convert_to_array
-
-# check environment variable for custom Python executable
-if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then
-  if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then
-    echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist"
-    return 1
-  fi
-  _colcon_python_executable="$COLCON_PYTHON_EXECUTABLE"
-else
-  # try the Python executable known at configure time
-  _colcon_python_executable="/usr/bin/python3"
-  # if it doesn't exist try a fall back
-  if [ ! -f "$_colcon_python_executable" ]; then
-    if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then
-      echo "error: unable to find python3 executable"
-      return 1
-    fi
-    _colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"`
-  fi
-fi
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-_colcon_prefix_sh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$1"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# get all commands in topological order
-_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_zsh_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh zsh)"
-unset _colcon_python_executable
-if [ -n "$COLCON_TRACE" ]; then
-  echo "$(declare -f _colcon_prefix_sh_source_script)"
-  echo "# Execute generated script:"
-  echo "# <<<"
-  echo "${_colcon_ordered_commands}"
-  echo "# >>>"
-  echo "unset _colcon_prefix_sh_source_script"
-fi
-eval "${_colcon_ordered_commands}"
-unset _colcon_ordered_commands
-
-unset _colcon_prefix_sh_source_script
-
-unset _colcon_prefix_zsh_COLCON_CURRENT_PREFIX
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/PKG-INFO b/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/PKG-INFO
deleted file mode 100644
index 59b425a79a72e98ee9bcafffada085b85d328236..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/PKG-INFO
+++ /dev/null
@@ -1,7 +0,0 @@
-Metadata-Version: 2.1
-Name: robobin
-Version: 0.0.0
-Summary: TODO: Package description
-Maintainer: paulw
-Maintainer-email: plw1g21@soton.ac.uk
-License: TODO: License declaration
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/SOURCES.txt b/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/SOURCES.txt
deleted file mode 100644
index 87703c5e30f54cd56d77173264cf63cfa42db567..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/SOURCES.txt
+++ /dev/null
@@ -1,22 +0,0 @@
-package.xml
-setup.cfg
-setup.py
-../../build/robobin/robobin.egg-info/PKG-INFO
-../../build/robobin/robobin.egg-info/SOURCES.txt
-../../build/robobin/robobin.egg-info/dependency_links.txt
-../../build/robobin/robobin.egg-info/entry_points.txt
-../../build/robobin/robobin.egg-info/requires.txt
-../../build/robobin/robobin.egg-info/top_level.txt
-../../build/robobin/robobin.egg-info/zip-safe
-launch/robobin_launch.py
-resource/robobin
-robobin/__init__.py
-robobin/api_node.py
-robobin/motor_control_node.py
-robobin/uwb_navigation_node.py
-robobin/helpers/__init__.py
-robobin/helpers/connection_manager.py
-robobin/helpers/message_handler.py
-test/test_copyright.py
-test/test_flake8.py
-test/test_pep257.py
\ No newline at end of file
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/dependency_links.txt b/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/dependency_links.txt
deleted file mode 100644
index 8b137891791fe96927ad78e64b0aad7bded08bdc..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/dependency_links.txt
+++ /dev/null
@@ -1 +0,0 @@
-
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/entry_points.txt b/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/entry_points.txt
deleted file mode 100644
index a569c6445838df1de986e4c1140c21af9733dc9c..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/entry_points.txt
+++ /dev/null
@@ -1,4 +0,0 @@
-[console_scripts]
-api_node = robobin.api_node:main
-motor_control_node = robobin.motor_control_node:main
-uwb_navigation_node = robobin.uwb_navigation_node:main
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/requires.txt b/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/requires.txt
deleted file mode 100644
index 49fe098d9e6bccd89482b34510da60ab28556880..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/requires.txt
+++ /dev/null
@@ -1 +0,0 @@
-setuptools
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/top_level.txt b/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/top_level.txt
deleted file mode 100644
index 2ca7c929754f574fe60649fed5f1333479af4ef7..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/top_level.txt
+++ /dev/null
@@ -1 +0,0 @@
-robobin
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/zip-safe b/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/zip-safe
deleted file mode 100644
index 8b137891791fe96927ad78e64b0aad7bded08bdc..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/zip-safe
+++ /dev/null
@@ -1 +0,0 @@
-
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__init__.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/__init__.py
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/__init__.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/__init__.cpython-312.pyc
deleted file mode 100644
index 0e477fb4b01dffd5afdcf737f3f29a725fc3d912..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/__init__.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/api_node.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/api_node.cpython-312.pyc
deleted file mode 100644
index 6522b485eef059932626b47badf3685ec979244e..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/api_node.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/control_feedback.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/control_feedback.cpython-312.pyc
deleted file mode 100644
index 61822e455e387086b7c0b5cd14b6f25d3cad4b31..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/control_feedback.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/encoder.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/encoder.cpython-312.pyc
deleted file mode 100644
index 2d7f9fb4757440f21c97b364955b5244b139677c..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/encoder.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/imu_node.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/imu_node.cpython-312.pyc
deleted file mode 100644
index 912367f0219eab28c18461c8f6ed2d0c6ac227e6..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/imu_node.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/motor_control_node.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/motor_control_node.cpython-312.pyc
deleted file mode 100644
index 4305f59b5aad93bc00191ae148f37fa95fcdf6f3..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/motor_control_node.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_navigation_node.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_navigation_node.cpython-312.pyc
deleted file mode 100644
index 091b8e7a83aacee222df5de3d88cf8f022dbc5c6..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_navigation_node.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_pathing_node.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_pathing_node.cpython-312.pyc
deleted file mode 100644
index 946502fe0ccc34b241319ea925c07c002f3d1fe8..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_pathing_node.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/api_node.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/api_node.py
deleted file mode 100644
index d83622c7d0d85e12c642f1fad0dfe9b411b6dd60..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin/api_node.py
+++ /dev/null
@@ -1,106 +0,0 @@
-
-# robobin/api_node.py
-from .helpers.message_handler import MessageHandler
-from .helpers.connection_manager import ConnectionManager
-
-from geometry_msgs.msg import Twist
-from geometry_msgs.msg import Point
-from std_msgs.msg import String
-import rclpy
-from rclpy.node import Node
-
-class ApiNode(Node):
-    def __init__(self):
-        super().__init__('api_node')
-        self.get_logger().info("ApiNode has been started.")
-
-        self.publisher_topics = {
-            "cmd_vel": self.create_publisher(Twist, '/cmd_vel', 10),
-            "nav_send": self.create_publisher(Twist, '/nav_send', 10), 
-            "nav_command": self.create_publisher(String, '/nav_command', 10),
-        }
-        self.location_subscriber = self.create_subscription(
-            Point,  # Message type
-            '/tag1_location',  # Topic
-            self.handle_location_update,  # Callback
-            10  # QoS depth
-        )
-        self.mode = "Manual"
-        self.called_locations = [] # List of  pairs of ip address and location
-        self.message_handler = MessageHandler(self)
-        self.connection_manager = ConnectionManager(self)
-
-        self.connection_manager.start()
-        self.get_logger().info("Connection manager started.")
-    def handle_client_connection(self, client_socket):
-        """Handles incoming TCP client connections."""
-        try:
-            while True:
-                data = client_socket.recv(1024).decode()
-                if not data:
-                    break
-                self.get_logger().info(f"Received data: {data}")
-                test = data.split(" ", 1)
-                self.get_logger().info(f"Received command: {test[0]}")
-                result = self.message_handler.handle_message(client_socket, data)
-        
-                # Check if the result is not None
-                if result is not None:
-                    topic, message = result  # Safely unpack after checking
-                    if topic is not None:
-                        self.get_logger().info(f"Publishing to topic: {topic}")
-                        self.publish_to_topic(topic, message)
-        finally:
-            client_socket.close()
-            self.get_logger().info("Client disconnected.")
-    def publish_to_topic(self, topic, message):
-        self.get_logger().info(f"Publishing to topic: {topic}")
-        """Publishes the message to the specified topic."""
-        if topic in self.publisher_topics:
-            publisher = self.publisher_topics[topic]
-
-            # Check if the topic is 'cmd_vel' and format the message as a Twist message
-            if topic == "cmd_vel" and isinstance(message, tuple):
-                linear_x, angular_z = message
-                twist_msg = Twist()
-                twist_msg.linear.x = linear_x
-                twist_msg.linear.y = 0.0
-                twist_msg.linear.z = 0.0
-                twist_msg.angular.x = 0.0
-                twist_msg.angular.y = 0.0
-                twist_msg.angular.z = angular_z
-
-                publisher.publish(twist_msg)
-                self.get_logger().info(f"Published to {topic}: linear_x={linear_x}, angular_z={angular_z}")
-            elif topic == "nav_command" and isinstance(message, str):
-                self.get_logger().info(f"Published to {topic}: {message}")
-                publisher.publish(String(data=message))
-            else:
-                self.get_logger().warning(f"Unhandled message type for topic: {topic}")
-        else:
-            self.get_logger().warning(f"Unknown topic: {topic}")
-    def handle_location_update(self, msg):
-        self.get_logger().info("Received updated location.")
-        self.get_logger().info(f"Received updated location: x={msg.x:.2f}, y={msg.y:.2f}")
-        """Callback for the /tag1_location topic."""
-        x = msg.x
-        y = msg.y
-        self.connection_manager.set_location(x, y)
-        self.get_logger().info(f"Received updated location: x={x:.2f}, y={y:.2f}")
-    def shutdown(self):
-        """Stops the connection manager."""
-        self.connection_manager.stop()
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = ApiNode()
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        node.shutdown()
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py
deleted file mode 100644
index 78a1edb74b03fbdf991c9e38c1b8980ee52b3945..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py
+++ /dev/null
@@ -1,320 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Twist
-from std_msgs.msg import Int64, Float64
-from gpiozero import PWMOutputDevice, DigitalOutputDevice
-import time
-from rclpy.clock import Clock
-from rclpy.time import Time
-import bisect
-
-
-
-# Example of how you could implement a simple PID controller
-class PIDController:
-    def __init__(self, kp, ki, kd):
-        self.kp = kp
-        self.ki = ki
-        self.kd = kd
-        self.prev_error = 0
-        self.integral = 0
-
-    def reset(self):
-        self.prev_error = 0
-        self.integral = 0
-
-    def calculate(self, error, dt):
-        self.integral += error * dt
-        derivative = (error - self.prev_error) / dt 
-        output = self.kp * error + self.ki * self.integral + self.kd * derivative
-        self.prev_error = error
-        return output
-
-
-
-
-class MotorControlNode(Node):
-    def __init__(self):
-        super().__init__('control_feedback_node')
-
-        # Initialize encoder values
-        self.encoder_left_steps = 0
-        self.encoder_right_steps = 0
-
-        # Desired speeds from cmd_vel
-        self.desired_linear_speed = 0.0
-        self.desired_angular_speed = 0.0
-
-        self.prev_left_steps = 0
-        self.prev_right_steps = 0
-
-        self.left_pwm = 0
-        self.right_pwm = 0
-
-        self.prev_desired_speed = 0.0
-
-
-        #Time
-        self.prev_time = time.time()
-        #self.prev_time = self.get_clock().now
-
-        
-        # Robot parameters
-        self.wheel_base = 0.40  
-        self.encoder_steps_per_rotation = 310  
-        self.wheel_radius = 0.075 
-
-        # Initialize the motors
-        self.motor = Motor(self,14,15,18, 17, 22, 27)
-
-        # PID controllers
-        self.pid_left_forward = PIDController(kp=0.5, ki=0.0, kd=0.001)
-        self.pid_right_forward = PIDController(kp=0.525, ki=0.0, kd=0.001)
-
-        self.pid_left_backward = PIDController(kp=0.525, ki=0.0, kd=0.001)
-        self.pid_right_backward = PIDController(kp=0.5, ki=0.0, kd=0.001)
-
-
-
-
-        # Subscribe to cmd_vel topic
-        self.subscription = self.create_subscription(
-            Twist,
-            '/cmd_vel',
-            self.cmd_vel_callback,
-            10
-        )
-
-        # Subscribe to encoder data
-        self.left_encoder_sub = self.create_subscription(
-            Int64,
-            'left_wheel_steps',
-            self.left_encoder_callback,
-            10
-        )
-        self.right_encoder_sub = self.create_subscription(
-            Int64,
-            'right_wheel_steps',
-            self.right_encoder_callback,
-            10
-        )
-
-        self.left_actual_speed_pub = self.create_publisher(Float64, 'left_actual_wheel_speed', 10)
-        self.right_actual_speed_pub = self.create_publisher(Float64, 'right_actual_wheel_speed', 10)
-        self.desired_speed_pub = self.create_publisher(Float64, 'desired_wheel_speed', 10)
-
-        # Timer to update motor speeds
-        self.control_timer = self.create_timer(0.1, self.control_loop)
-
-        self.get_logger().info('Motor control node with encoder feedback has been started.')
-
-    def cmd_vel_callback(self, msg):
-        # Store desired speeds
-        self.desired_linear_speed = msg.linear.x  # Forward/backward speed
-        self.desired_angular_speed = msg.angular.z  # Turning rate
-
-        # if (self.desired_linear_speed >= 0 and self.prev_desired_speed < 0) or (self.desired_linear_speed < 0 and self.prev_desired_speed >= 0):
-
-        #     self.pid_left_forward.reset()
-        #     self.pid_right_forward.reset()
-        #     self.pid_left_backward.reset()
-        #     self.pid_right_backward.reset()
-
-
-
-        
-
-        self.prev_desired_speed = self.desired_linear_speed
-
-    def left_encoder_callback(self, msg):
-        self.encoder_left_steps = msg.data
-
-    def right_encoder_callback(self, msg):
-        self.encoder_right_steps = msg.data
-
-    
-    def control_loop(self):
-
-        if self.desired_linear_speed >= 0:
-            # Forward motion
-            left_pid = self.pid_left_forward
-            right_pid = self.pid_right_forward
-        else:
-            # Backward motion
-            left_pid = self.pid_left_backward
-            right_pid = self.pid_right_backward
-
-        if (self.desired_linear_speed == 0) and (self.desired_angular_speed == 0):
-            self.stop_motors()
-            self.pid_left_forward.reset()
-            self.pid_right_forward.reset()
-            self.pid_left_backward.reset()
-            self.pid_right_backward.reset()
-            self.left_pwm =0
-            self.right_pwm =0
-            return
-
-
-
-
-        #Calculate the actual speed
-        #-------------------------------
-        # Calculate elapsed time
-        current_time = time.time()
-        #dt = current_time - self.prev_time
-        dt = max(current_time - self.prev_time, 0.01)  # Prevent dt from being too small
-        #dt = max(current_time - self.prev_time, 1e-6)  # Avoid zero or too small dt
-        if dt == 0:
-            return
-        self.prev_time = current_time
-
-        # self.prev_time = self.get_clock().now()
-        # current_time = self.get_clock().now()
-        # dt = (current_time - self.prev_time).to_sec()
-        # if dt <= 0.0:
-        #     return
-        # self.prev_time = current_time
-
-        #Actual Speed calculation
-        #------------------------------------
-        # Calculate change in encoder steps
-        delta_left_steps = self.encoder_left_steps - self.prev_left_steps
-        delta_right_steps = self.encoder_right_steps - self.prev_right_steps
-
-        self.prev_left_steps = self.encoder_left_steps
-        self.prev_right_steps = self.encoder_right_steps
-
-        # Calculate rotational speeds (RPS)
-        left_rps = delta_left_steps / (self.encoder_steps_per_rotation * dt)
-        right_rps = delta_right_steps / (self.encoder_steps_per_rotation * dt)
-
-        # Convert to linear speed (m/s)
-        left_speed_actual = left_rps * 2 * 3.14159 * self.wheel_radius
-        right_speed_actual = right_rps * 2 * 3.14159 * self.wheel_radius
-
-
-
-        #Desired Speed calculation
-        #------------------------------------
-        # Desired speeds for left and right wheels
-        left_speed_desired = self.desired_linear_speed - (self.desired_angular_speed * self.wheel_base / 2.0)
-        right_speed_desired = self.desired_linear_speed + (self.desired_angular_speed * self.wheel_base / 2.0)
-
-
-
-        # Speed Errors calculation
-        #------------------------------------
-        left_error = left_speed_desired - left_speed_actual
-        right_error = right_speed_desired - right_speed_actual
-
- 
-
-        # Use PID controllers for left and right wheels
-        left_pwm_error = left_pid.calculate(left_error, dt)
-        right_pwm_error = right_pid.calculate(right_error, dt)
-
-        self.left_pwm +=   left_pwm_error
-        self.right_pwm +=  right_pwm_error
-
-
-
-        # Ensure PWM values are within [-1, 1]
-        left_pwm = max(-1, min(1, self.left_pwm))
-        right_pwm = max(-1, min(1, self.right_pwm))
-
-        # Apply PWM values to motors
-        self.motor.set_pwm(left_pwm, right_pwm)
-
-        
-
-
-        # Publish actual speeds
-        left_actual_speed_msg = Float64()
-        left_actual_speed_msg.data = left_speed_actual
-        self.left_actual_speed_pub.publish(left_actual_speed_msg)
-
-        right_actual_speed_msg = Float64()
-        right_actual_speed_msg.data = right_speed_actual
-        self.right_actual_speed_pub.publish(right_actual_speed_msg)
-
-        desired_speed_msg = Float64()
-        desired_speed_msg.data = right_speed_desired
-        self.desired_speed_pub.publish(desired_speed_msg)
-
-
-        # Debugging info
-        # self.get_logger().info(f'Left PWM IN: {self.left_pwm:.2f}, Right PWM IN: {right_pwm:.2f}')
-        # self.get_logger().info(f'Left Speed Actual: {left_speed_actual:.2f}, Right Speed Actual: {right_speed_actual:.2f}')
-        # self.get_logger().info(f'Left Error: {left_error:.2f}, Right Error: {left_pwm_error:.2f}')
-        # self.get_logger().info(f'Left_speed_desired: {left_speed_desired:.2f}, Right_speed_desired: {right_speed_desired:.2f}')
-        # self.get_logger().info('-----------------------------------------------------------------')
-
-
-    def stop_motors(self):
-        self.motor.stop()
-        # self.get_logger().info('Motors have been stopped.')
-
-class Motor:
-    def __init__(self,node, EnaA, In1A, In2A, EnaB, In1B, In2B):
-
-        self.node = node
-        # Left motor control pins
-        self.pwmA = PWMOutputDevice(EnaA)
-        self.in1A = DigitalOutputDevice(In1A)
-        self.in2A = DigitalOutputDevice(In2A)
-
-        # Right motor control pins
-        self.pwmB = PWMOutputDevice(EnaB)
-        self.in1B = DigitalOutputDevice(In1B)
-        self.in2B = DigitalOutputDevice(In2B)
-
-    def set_pwm(self, left_pwm, right_pwm):
-
-        #Deadband to prevent the motors from responding to very small PWM values that could cause jitter.
-        DEADZONE = 0.002
-
-        if abs(left_pwm) < DEADZONE:
-            self.pwmA.value = 0
-            self.in1A.off()
-            self.in2A.off()
-        else:
-            self.pwmA.value = abs(left_pwm)
-            self.in1A.value = left_pwm >  0
-            self.in2A.value = left_pwm < 0
-
-        if abs(right_pwm) < DEADZONE:
-            self.pwmB.value = 0
-            self.in1B.off()
-            self.in2B.off()
-        else:
-            self.pwmB.value = abs(right_pwm)
-            self.in1B.value = right_pwm >  0
-            self.in2B.value = right_pwm < 0
-
-        #self.node.get_logger().info(f"Left Motor PWM: Speed={left_pwm}, Right Motor PWM: Speed={right_pwm}")
-
-    def stop(self):
-        # Stop both motors
-        self.pwmA.value = 0
-        self.pwmB.value = 0
-        self.in1A.off()
-        self.in2A.off()
-        self.in1B.off()
-        self.in2B.off()
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = MotorControlNode()
-
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.stop_motors()
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/encoder.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/encoder.py
deleted file mode 100644
index f646d3dc16cc781b870f52bdbbfc5b5e6e3cbcd0..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin/encoder.py
+++ /dev/null
@@ -1,63 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from std_msgs.msg import Int64
-from gpiozero import RotaryEncoder, InputDevice
-
-
-
-class EncoderReaderNode(Node):
-    def __init__(self):
-        super().__init__('encoder_reader_node')
-
-        motor1A = 5
-        motor1B = 6
-        motor2A = 20
-        motor2B = 21
-
-        self.encoder_left = RotaryEncoder(a = motor1A,b = motor1B, max_steps=0)
-        self.encoder_right = RotaryEncoder(a = motor2A,b = motor2B, max_steps=0)
-
-        # Publishers for encoder steps
-        self.left_encoder_pub = self.create_publisher(Int64, 'left_wheel_steps', 10)
-        self.right_encoder_pub = self.create_publisher(Int64, 'right_wheel_steps', 10)
-
-        # Timer to read encoders
-        self.timer = self.create_timer(0.1, self.publish_encoder_steps)
-
-        self.get_logger().info('Encoder reader node has been started.')
-
-    def publish_encoder_steps(self):
-        # Read encoder steps
-        left_steps = self.encoder_left.steps
-        right_steps = -(self.encoder_right.steps)
-
-        # Create messages
-        left_msg = Int64()
-        left_msg.data = left_steps
-
-        right_msg = Int64()
-        right_msg.data = right_steps
-
-        # Publish messages
-        self.left_encoder_pub.publish(left_msg)
-        self.right_encoder_pub.publish(right_msg)
-
-        # Log the steps
-        #self.get_logger().info(f'Left Steps: {left_steps}, Right Steps: {right_steps}')
-
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = EncoderReaderNode()
-
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/__init__.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/__init__.cpython-312.pyc
deleted file mode 100644
index 3ba48010744f2b3c377c0be46a6bfd08be5e4c4e..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/__init__.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/connection_manager.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/connection_manager.cpython-312.pyc
deleted file mode 100644
index e495321b355d6e33afcba4842e73cc323cb7c086..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/connection_manager.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/graph_maker.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/graph_maker.cpython-312.pyc
deleted file mode 100644
index f22e9c1b70f1f62f37d428146dfc43c8b925f29e..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/graph_maker.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/message_handler.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/message_handler.cpython-312.pyc
deleted file mode 100644
index 6012af0259419e3aabbc861ee119a5a3ba904699..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/message_handler.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/realtime_location_cli_only.cpython-312.pyc b/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/realtime_location_cli_only.cpython-312.pyc
deleted file mode 100644
index dac4aac1684a6186f8333d3cba4cad02f785e2b7..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/realtime_location_cli_only.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py
deleted file mode 100644
index 0fb010b26ca2d962796eb49eee48ab8836705d9f..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py
+++ /dev/null
@@ -1,88 +0,0 @@
-import socket
-import threading
-import time
-import json
-
-class ConnectionManager:
-    def __init__(self, api_node, udp_ip="255.255.255.255", udp_port=5005, listen_port=5006):
-        self.api_node = api_node
-        self.UDP_IP = udp_ip
-        self.UDP_PORT = udp_port
-        self.LISTEN_PORT = listen_port
-        self.stop_event = threading.Event()
-        self.location = [0, 0]  # At some point, this will be retrieved from the navigation node
-                
-    def start(self):
-        """Starts listening for connections and broadcasting presence."""
-        self.listen_thread = threading.Thread(target=self.listen_for_connections)
-        self.broadcast_thread = threading.Thread(target=self.broadcast_presence)
-        self.listen_thread.start()
-        self.broadcast_thread.start()
-
-    def listen_for_connections(self):
-        """Listens for UDP 'CONNECT' messages and sets up TCP connections."""
-        udp_sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
-        udp_sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
-        udp_sock.bind(('', self.LISTEN_PORT))
-
-        while not self.stop_event.is_set():
-            try:
-                data, addr = udp_sock.recvfrom(1024)
-                if data.decode() == "CONNECT":
-                    self.api_node.get_logger().info(f"Received CONNECT message from {addr}")
-                    tcp_sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
-                    tcp_sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
-                    tcp_sock.bind(('', self.LISTEN_PORT))
-                    tcp_sock.listen(1)
-                    client_socket, client_addr = tcp_sock.accept()
-                    self.api_node.get_logger().info(f"Client connected from {client_addr}")
-                    threading.Thread(target=self.api_node.handle_client_connection, args=(client_socket,)).start()
-            except socket.timeout:
-                continue
-            except OSError:
-                break
-
-        udp_sock.close()
-        print("Stopped listening for connections.")
-
-    def broadcast_presence(self):
-        """Broadcasts presence periodically over UDP."""
-        sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
-        sock.setsockopt(socket.SOL_SOCKET, socket.SO_BROADCAST, 1)
-
-        while not self.stop_event.is_set():
-            try:
-                mode = self.api_node.mode
-                
-                # JSON-formatted message
-                message = {
-                    "type": "ROBOBIN_PRESENT",
-                    "data": {
-                        "Location": self.location,
-                        "Mode": mode,
-                       
-                    }
-                }
-
-                # Serialize the JSON message to a string
-                json_message = json.dumps(message).encode('utf-8')
-
-                # Send the JSON message over UDP
-                sock.sendto(json_message, (self.UDP_IP, self.UDP_PORT))
-                self.api_node.get_logger().info("Broadcasting JSON presence.")
-                self.api_node.get_logger().info(f"Location: {self.location}, Mode: {mode}")
-                time.sleep(2)
-            except OSError:
-                break
-
-        sock.close()
-        self.api_node.get_logger().info("Stopped broadcasting presence.")
-    def set_location(self, x, y):
-        """Sets the location of the robot."""
-        self.location = [x, y]
-    def stop(self):
-        """Stops the connection manager."""
-        self.stop_event.set()
-    
-if __name__ == "__main__":
-    ConnectionManager(None).start()
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py
deleted file mode 100644
index 202fc34fbdb12d8307c22f7da6bdfc946c351040..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py
+++ /dev/null
@@ -1,112 +0,0 @@
-import json
-import time
-import os
-from realtime_location_cli_only import AnchorTagCLI
-
-class GraphMaker:
-    def __init__(self, port="COM11", testing=False):
-        self.app = AnchorTagCLI(port=port, testing=testing)
-        self.graph = {
-            "name": "Lab 1 Extended",
-            "nodes": [],
-            "connections": []
-        }
-        self.previous_node_index = None
-
-    def call_bpm_and_store_anchors(self):
-        self.app.call_bpm()
-        for name, (x, y) in self.app.anchors.items():
-            self.graph["nodes"].append({
-                "name": name,
-                "x": x,
-                "y": y
-            })
-
-        # Initialize connections matrix with False
-        num_nodes = len(self.graph["nodes"])
-        self.graph["connections"] = [[False] * num_nodes for _ in range(num_nodes)]
-
-        print("Anchor coordinates stored successfully.")
-
-    def start_session(self):
-        print("Waiting for 'start' command...")
-        while True:
-            user_input = input("Enter 'start' to begin adding nodes or 'quit' to exit: ").strip().lower()
-            if user_input == "start":
-                print("Session started. Type 'save' to add nodes, 'finish' to save the graph, or 'quit' to exit.")
-                break
-            elif user_input == "quit":
-                print("Exiting...")
-                exit()
-
-    def add_node_and_connect(self):
-        print(self.app.tag_distances)
-        distances = self.app.serial_buffer.getRangingDistances()
-
-        tag1_x, tag1_y = self.app.update_distances_and_calculate_tags()
-        print(f"{tag1_x}, {tag1_y}")
-        if tag1_x is None or tag1_y is None:
-            print("Failed to determine tag position. Skipping node creation.")
-            return
-
-        new_node_index = len(self.graph["nodes"])
-
-        # Add new node
-        self.graph["nodes"].append({
-            "name": f"Node{new_node_index+1}",
-            "x": tag1_x,
-            "y": tag1_y
-        })
-
-        # Dynamically resize the connections matrix
-        for row in self.graph["connections"]:
-            row.append(False)  # Add a column for the new node
-        self.graph["connections"].append([False] * (new_node_index + 1))  # Add a new row
-
-        # Update connections
-        if self.previous_node_index is not None:
-            self.graph["connections"][self.previous_node_index][new_node_index] = True
-            self.graph["connections"][new_node_index][self.previous_node_index] = True
-
-        self.previous_node_index = new_node_index
-
-        print(f"Node {new_node_index+1} added at ({tag1_x:.2f}, {tag1_y:.2f}).")
-
-    def save_graph(self):
-        directory = "/Users/paulwinpenny/Documents/GitHub/robobin/Wireless_Communication/UWB/Beacons_tag_position/output"
-        os.makedirs(directory, exist_ok=True)  # Create the directory if it doesn't exist
-        file_path = os.path.join(directory, "graph.json")
-        with open(file_path, "w") as f:
-            json.dump(self.graph, f, indent=2)
-        print(f"Graph saved to '{file_path}'.")
-
-
-    def run(self):
-        while True:
-            user_input = input("Enter command ('bpm', 'start', 'save', 'finish', 'quit'): ").strip().lower()
-            if user_input == "bpm":
-                self.call_bpm_and_store_anchors()
-            elif user_input == "start":
-                self.start_session()
-                while True:
-                    user_input = input("Enter 'save' to add a node, 'finish' to save and exit, or 'quit' to exit: ").strip().lower()
-                    if user_input == "save":
-                        self.add_node_and_connect()
-                    elif user_input == "finish":
-                        self.save_graph()
-                        print("Session finished.")
-                        exit()
-                    elif user_input == "quit":
-                        print("Exiting without saving.")
-                        exit()
-                    else:
-                        print("Invalid command. Try 'save', 'finish', or 'quit'.")
-            elif user_input == "quit":
-                print("Exiting...")
-                break
-            else:
-                print("Invalid command. Try 'bpm', 'start', 'save', 'finish', or 'quit'.")
-
-if __name__ == "__main__":
-    graph_maker = GraphMaker(port="/dev/tty.usbmodem14101", testing=False)
-    graph_maker.run()
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py
deleted file mode 100644
index 72ca4a5795a8a5190e77e67e41b42bfa8d4e3a11..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py
+++ /dev/null
@@ -1,193 +0,0 @@
-# robobin/message_handler.py
-import time
-import json
-
-import os
-class MessageHandler:
-    def __init__(self, api_node, testing=False):
-        self.api_node = api_node
-        self.testing = testing
-        self.handlers = {
-            "PING": self.handle_ping,
-            "TIME": self.handle_time_request,
-            "MANUALCTRL": self.handle_manual_control,
-            "SETMODE": self.handle_set_mode,
-            "STOP": self.handle_stop,
-            "CALLME": self.handle_call_me,
-            "BPM": self.handle_call_bpm,
-            "REQMAP": self.handle_request_map,
-        }
-
-    def handle_message(self, client_socket, raw_message):
-        """Parses the incoming message and routes the command to the appropriate handler."""
-        command, *args = raw_message.split(" ", 1)
-        #self.api_node.logger.info(f"Received command: {command}")
-        #self.api_node.logger.info(f"Received arguments: {args}")
-        data = args[0] if args else None
-        handler = self.handlers.get(command, self.handle_unknown_message)
-        return handler(client_socket, data)
-    
-    def handle_call_me(self, client_socket, message):
-        #Message says  CALLME,(212.9638, 283.98108), extract location and ip address
-        if client_socket is None:
-            ip = "Fake IP"
-        else:
-            ip = client_socket.getpeername()[0]
-        print(message)
-        location = message.strip() # Remove parentheses
-        location = f"{location}"  # Add parentheses back for proper formatting
-        
-        for existing_ip, _ in self.api_node.called_locations:
-            if existing_ip == ip:
-                client_socket.sendall(b"User already requested location")
-                return None  # IP already in the list, exit early
-
-        self.api_node.called_locations.append((ip, location))
-    
-        response = f"Queue Position = {len(self.api_node.called_locations)-1}".encode()
-        client_socket.sendall(response)
-        print("nav_command", location)
-        return "nav_command", location
-    
-    def handle_stop(self, client_socket, _):
-        """Handles the STOP command."""
-        response = b"Stopping the robot"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        return "cmd_vel", (0.0, 0.0)
-    
-    def handle_ping(self, client_socket, _):
-        """Responds with a PONG message."""
-        response = b"PONG"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-
-        return None
-    def handle_set_mode(self, client_socket, message):
-        """Handles mode setting commands."""
-        response = f"Setting mode to {message}".encode()
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        self.api_node.mode = message
-        return None
-    def handle_time_request(self, client_socket, _):
-        """Sends the current server time."""
-        response = time.ctime().encode()
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-
-        return None
-    def handle_call_bpm(self, client_socket, _):
-        """Handles the CALLBPM command."""
-        response = b"Calling BPM, Graph will be reset"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-
-        return "nav_command","BPM"
-    def handle_manual_control(self, client_socket, message):
-        """Handles manual control commands: W, A, S, D."""
-        # W: linear.x = 0.5, angular.z = 0
-        # A: linear.x = 0, angular.z = 0.5
-        # S: linear.x = -0.5, angular.z = 0
-        # D: linear.x = 0, angular.z = -0.5
-        
-        directions = {
-            "W": (0.5, 0),    # Move forward
-            "A": (0, 0.5),    # Turn left
-            "S": (-0.5, 0),   # Move backward
-            "D": (0, -0.5)    # Turn right
-        }
-        
-        # Get direction data and ensure it's a tuple of floats
-        raw_response_data = directions.get(message.strip().upper(), (0, 0))
-        response_data = (float(raw_response_data[0]), float(raw_response_data[1]))  # Explicitly cast to float
-        
-        # Send feedback to the client
-        response = f"Manual control command received: {response_data}".encode()
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        
-        print("Processed manual control command:", response_data)
-        return "cmd_vel", response_data
-
-    def handle_request_map(self, client_socket, _):
-            """Handles the REQMAP command."""
-            # Relative path to the JSON file
-            graph_file_path = os.path.join("src", "robobin", "robobin", "graphs", "graph.json")
-
-            try:
-                # Load the graph JSON file
-                with open(graph_file_path, 'r') as f:
-                    graph_data = json.load(f)
-
-                # Serialize the JSON data to a string
-                graph_json = json.dumps(graph_data)
-                # Send the JSON response back to the client
-                if self.testing:
-                    print("Sending map data:", graph_json)
-                else:
-                    client_socket.sendall(graph_json.encode())
-
-                return None
-
-            except FileNotFoundError:
-                error_message = f"Error: File not found at {graph_file_path}"
-                if self.testing:
-                    print(error_message)
-                else:
-                    client_socket.sendall(error_message.encode())
-
-                return None
-
-            except json.JSONDecodeError as e:
-                error_message = f"Error: Failed to decode JSON - {str(e)}"
-                if self.testing:
-                    print(error_message)
-                else:
-                    client_socket.sendall(error_message.encode())
-
-                return None
-
-            except Exception as e:
-                error_message = f"Error: {str(e)}"
-                if self.testing:
-                    print(error_message)
-                else:
-                    client_socket.sendall(error_message.encode())
-
-                return None
-    def handle_unknown_message(self, client_socket, _):
-        """Handles unknown commands."""
-        response = b"Unknown command"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        return None
-    
-# Test class without api_node and with testing enabled
-if __name__ == "__main__":
-    message_handler = MessageHandler(None, testing=True)
-    assert message_handler.handle_message(None, "PING") is None
-    assert message_handler.handle_message(None, "TIME") is None
-    assert message_handler.handle_message(None, "MANUALCTRL W") == ("cmd_vel", (0.5, 0))
-    assert message_handler.handle_message(None, "MANUALCTRL A") == ("cmd_vel", (0, 0.5))
-    assert message_handler.handle_message(None, "MANUALCTRL S") == ("cmd_vel", (-0.5, 0))
-    assert message_handler.handle_message(None, "MANUALCTRL D") == ("cmd_vel", (0, -0.5))
-
-    assert message_handler.handle_message(None, "STOP") == ("cmd_vel", (0.0, 0.0))
-    assert message_handler.handle_message(None, "CALLME (212.9638, 283.98108)") == ("nav_command", "(212.9638, 283.98108)")
-    assert message_handler.handle_message(None, "UNKNOWN") is None
-    assert message_handler.handle_message(None, "REQMAP") is None
\ No newline at end of file
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py
deleted file mode 100644
index 2c9284f5b76954d74374a8da44127e6f7db673fe..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py
+++ /dev/null
@@ -1,279 +0,0 @@
-import time
-import numpy as np
-import serial
-from scipy.optimize import least_squares
-
-# Define test values at the top of the file for easy modification
-TEST_MEASURED_DISTANCES = [302, 463, 286, 304, 418, 328]
-TEST_TAG1_DISTANCES = [22, 107, 246, 295]
-TEST_TAG2_DISTANCES = [100, 100, 100, 100]
-
-class SerialBuffer:
-    def __init__(self, port):
-        self.ser = serial.Serial(port, 115200, timeout=1)
-
-    def readFromDevice(self, expectedLines=1):
-        lines = []
-        # Attempt to read expected lines; if device is slow, you may need retries
-        while len(lines) < expectedLines:
-            if self.ser.in_waiting:
-                line = self.ser.readline().decode().strip()
-                if line:
-                    lines.append(line)
-            else:
-                time.sleep(0.01)
-        return lines
-
-    def getBeaconPositioningDistances(self):
-        """Reads the measured distances (A,E,D,B,F,C) from the device."""
-        self.writeToDevice("bpm")
-        buffer = self.readFromDevice(1)[0]
-        values = list(map(float, buffer.split(" ")))
-        return values
-
-    def getRangingDistances(self):
-        """Reads the distances from the tags to the anchors."""
-        self.writeToDevice("rng")
-        lines = self.readFromDevice(2)
-        print(lines)
-        distances = []
-        # First line: Tag 1 distances
-        distances.append(list(map(float, lines[0][1:].split(" "))))
-        # Second line: Tag 2 distances or "0"
-        if lines[1] != "1":
-            distances.append(list(map(float, lines[1][1:].split(" "))))
-        else:
-            distances.append(None)
-        return distances
-
-    def writeToDevice(self, value):
-        self.ser.write((value + "\n").encode())
-
-    def __del__(self):
-        print("Closing port")
-        self.ser.close()
-
-
-class AnchorTagCLI:
-    def __init__(self, port="/dev/tty.usbmodem14101", testing=False):
-        self.testing = testing
-        self.serial_buffer = SerialBuffer(port)
-
-        # Distances between anchors (A,E,D,B,F,C)
-        # Corresponding to the measured_distances in original code.
-        self.measured_distances = [0.0]*6
-
-        # Distances from Tag 1 to anchors: A1, A2, A3, A4
-        self.tag_distances = {"A1": 0.0, "A2": 0.0, "A3": 0.0, "A4": 0.0}
-
-        # Distances from Tag 2 to anchors: A1, A2, A3, A4
-        self.tag2_distances = {"A1": 0.0, "A2": 0.0, "A3": 0.0, "A4": 0.0}
-
-        self.anchors = {}
-        self.anchorHeight = 250
-        self.anchors_coords_known = False
-
-        if self.testing:
-            # Set predefined test distances
-            for i, dist in enumerate(TEST_MEASURED_DISTANCES):
-                self.measured_distances[i] = dist
-
-            for (anchor, dist) in zip(self.tag_distances.keys(), TEST_TAG1_DISTANCES):
-                self.tag_distances[anchor] = dist
-
-            for (anchor, dist) in zip(self.tag2_distances.keys(), TEST_TAG2_DISTANCES):
-                self.tag2_distances[anchor] = dist
-
-    def determine_anchor_coords(self):
-        try:
-            measured_distances = np.array(self.measured_distances)
-            y_A = measured_distances[2]  # Distance from A to D
-
-            # Guess for B based on distance A-B and B-D
-            x_B = measured_distances[0] / 2
-            y_B = measured_distances[4] / 2 + 200  # Start y_B above y_C
-
-            # Guess for C with symmetrical logic
-            x_C = -measured_distances[5] / 2  # Allow for negative x_C
-            y_C = -measured_distances[1] / 2  # Allow for negative y_C
-
-            initial_guess = [x_B, y_B, x_C, y_C, y_A]
-
-            min_dist = min(measured_distances)
-            max_dist = max(measured_distances)
-            lower_bounds = [-max_dist, -max_dist, -max_dist, -max_dist, min_dist / 2]
-            upper_bounds = [max_dist * 1.5 for i in range(5)]
-
-            def error_function(variables, measured):
-                x_B, y_B, x_C, y_C, y_A = variables
-
-                # Map measured distances to a, e, d, b, f, c
-                a_measured, e_measured, d_measured, b_measured, f_measured, c_measured = measured
-
-                # Compute each distance
-                a_calc = np.sqrt((x_B - 0)**2 + (y_B - y_A)**2)  # A-B
-                b_calc = np.sqrt((x_C - x_B)**2 + (y_C - y_B)**2)  # B-C
-                c_calc = np.sqrt(x_C**2 + y_C**2)                 # C-D
-                d_calc = y_A                                      # A-D
-                e_calc = np.sqrt(x_C**2 + (y_C - y_A)**2)         # A-C
-                f_calc = np.sqrt(x_B**2 + y_B**2)                 # B-D
-
-                # Residuals
-                r_a = a_calc - a_measured
-                r_b = b_calc - b_measured
-                r_c = c_calc - c_measured
-                r_d = d_calc - d_measured
-                r_e = e_calc - e_measured
-                r_f = f_calc - f_measured
-
-                # Add a smoother penalty if y_B <= y_C
-                penalty = 1e3 * max(0, y_C - y_B + 10)  # Soft penalty to enforce constraint
-
-                return [r_a, r_b, r_c, r_d, r_e, r_f, penalty]
-
-            result = least_squares(error_function, initial_guess, args=(measured_distances,), bounds=(lower_bounds, upper_bounds), loss='soft_l1')
-
-            x_B, y_B, x_C, y_C, y_A = result.x
-            self.anchors = {
-                "A1": (0, y_A, self.anchorHeight),
-                "A2": (x_B, y_B, self.anchorHeight),
-                "A3": (x_C, y_C, self.anchorHeight),
-                "A4": (0, 0, self.anchorHeight)
-            }
-            return {k: (round(v[0], 2), round(v[1], 2)) for k, v in self.anchors.items()}
-        except Exception as e:
-            print(f"Error generating anchors: {e}")
-
-    def calculate_tag_coordinates(self, tag_distances):
-        if not self.anchors_coords_known or len(self.anchors) < 3:
-            return None, None
-     
-        available_beacons = []
-        available_distances = []
-        for key in tag_distances.keys():
-            d = max(float(tag_distances[key]), 0)
-            available_distances.append(d)
-            available_beacons.append(self.anchors[key])
-
-        if len(available_beacons) < 3:
-            return None, None
-
-        heights = []
-        for (bx, by, bz), d_measured in zip(available_beacons, available_distances):
-            horizontal_distance = np.sqrt((bx - 0)**2 + (by - 0)**2)  # Assume tag starts at (0, 0)
-            estimated_z = np.sqrt(max(0, d_measured**2 - horizontal_distance**2))  # Ensure non-negative
-            heights.append(bz - estimated_z)  # Estimate tag height relative to beacon
-
-        initial_z = max(0, min(self.anchorHeight, np.mean(heights)))  # Constrain height to [0, 200]
-        
-        beacon_xs = [b[0] for b in available_beacons]
-        beacon_ys = [b[1] for b in available_beacons]
-        initial_guess = [np.mean(beacon_xs), np.mean(beacon_ys), initial_z]
-
-        # Define bounds for the tag position
-        x_min = min(beacon_xs) - 1000  # Add a small margin around the beacons
-        x_max = max(beacon_xs) + 1000
-        y_min = min(beacon_ys) - 1000
-        y_max = max(beacon_ys) + 1000
-        z_min = 0.0  # Tag's height cannot be below the ground
-        z_max = self.anchorHeight  # Tag's height cannot exceed the beacon height
-        bounds = ([x_min, y_min, z_min], [x_max, y_max, z_max])
-        
-        def error_function(vars):
-            x, y, z= vars
-            residuals = []
-            for (bx, by, bz), d_measured in zip(available_beacons, available_distances):
-                d_computed = np.sqrt((x - bx)**2 + (y - by)**2 + (z - bz)**2)
-                residuals.append(d_computed - d_measured)
-            return residuals
-
-        result = least_squares(error_function, initial_guess, bounds=bounds, loss='soft_l1')
-        # self.get_logger().info(f"Optimization result: {result.x}")
-        return tuple(result.x)
-
-
-    def call_bpm(self):
-        if self.testing:
-            beacon_distances = TEST_MEASURED_DISTANCES
-        else:
-            beacon_distances = self.serial_buffer.getBeaconPositioningDistances()
-
-        for i, distance in enumerate(beacon_distances):
-            if i < len(self.measured_distances):
-                self.measured_distances[i] = distance
-
-        determined_anchor_coords = self.determine_anchor_coords()
-        if determined_anchor_coords:
-            self.anchors_coords_known = True
-            print("Anchor coordinates determined:")
-            for anchor, coords in determined_anchor_coords.items():
-                print(f"{anchor}: {coords}")
-
-    def update_distances_and_calculate_tags(self):
-        if not self.anchors_coords_known:
-            return
-
-        if self.testing:
-            ranging_distances = [TEST_TAG1_DISTANCES, TEST_TAG2_DISTANCES]
-        else:
-            ranging_distances = self.serial_buffer.getRangingDistances()
-
-        # Update tag 1 distances
-        if ranging_distances[0] is not None:
-            for i, distance in enumerate(ranging_distances[0]):
-                anchor = list(self.tag_distances.keys())[i]
-                self.tag_distances[anchor] = distance
-
-        # Update tag 2 distances
-        if ranging_distances[1] is not None:
-            for i, distance in enumerate(ranging_distances[1]):
-                anchor = list(self.tag2_distances.keys())[i]
-                self.tag2_distances[anchor] = distance
-
-        # Now calculate both tags
-        tag1_x, tag1_y, tag1_z = self.calculate_tag_coordinates(self.tag_distances)
-        valid_tag2_distances = [dist for dist in self.tag2_distances.values() if dist > 0]
-
-        # Check if there are enough valid distances for Tag 2
-        if len(valid_tag2_distances) < 3:
-            print(f"Insufficient valid distances for Tag 2: {len(valid_tag2_distances)} provided.")
-            tag2_x, tag2_y, tag2_z = None, None, None
-        else:
-            tag2_x, tag2_y, tag2_z = self.calculate_tag_coordinates(self.tag2_distances)
-
-        print("Tag Positions:")
-        if tag1_x is not None and tag1_y is not None:
-            print(f"Tag 1: ({tag1_x:.2f}, {tag1_y:.2f}, {tag1_z:.2f})")
-        else:
-            print("Tag 1: Not enough data")
-
-        if tag2_x is not None and tag2_y is not None:
-            print(f"Tag 2: ({tag2_x:.2f}, {tag2_y:.2f}, {tag2_z:.2f})")
-        else:
-            print("Tag 2: Not enough data")
-
-      
-        if tag1_x is not None and tag1_y is not None and tag2_x is not None and tag2_y is not None:
-            dx = tag2_x - tag1_x
-            dy = tag2_y - tag1_y
-            dz = tag2_z - tag1_z
-            displacement = np.sqrt(dx**2 + dy**2 + dz**2)
-            angle_deg = np.degrees(np.arctan2(dy, dx))
-            if angle_deg < 0:
-                angle_deg += 360
-            print(f"Direction from Tag1 to Tag2: dx={dx:.2f}, dy={dy:.2f}, displacement={displacement:.2f}, angle={angle_deg:.2f}°")
-        return tag1_x, tag1_y
-
-if __name__ == "__main__":
-    app = AnchorTagCLI(port="/dev/tty.usbmodem14101", testing=False)
-    while True:
-        user_input = input("Enter command ('bpm' to set anchors, or 'quit' to exit): ").strip().lower()
-        if user_input == "bpm":
-            app.call_bpm()
-            print("Switching to continuous ranging updates (simulating 'rng' messages)...")
-            while True:
-                app.update_distances_and_calculate_tags()
-                time.sleep(1)
-        elif user_input == "quit":
-            print("Exiting program.")
-            break
\ No newline at end of file
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py
deleted file mode 100644
index d20c2dad0c8ab6525395a00d74ce5833f1fa2d94..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py
+++ /dev/null
@@ -1,95 +0,0 @@
-#!/usr/bin/env python3
-
-import rclpy
-from rclpy.node import Node
-from sensor_msgs.msg import Imu
-from smbus2 import SMBus
-import time
-import math
-
-class BNO055Publisher(Node):
-    def __init__(self):
-        super().__init__('imu_node')
-        self.publisher_ = self.create_publisher(Imu, 'imu', 10)
-        self.timer = self.create_timer(0.1, self.timer_callback)
-        self.bus = SMBus(1)
-        self.address = 0x28
-        self.init_bno055()
-        time.sleep(1)
-
-    def write_register(self, register, value):
-        self.bus.write_byte_data(self.address, register, value)
-
-    def read_register(self, register, length=1):
-        if length == 1:
-            return self.bus.read_byte_data(self.address, register)
-        else:
-            return self.bus.read_i2c_block_data(self.address, register, length)
-
-    def init_bno055(self):
-        # Switch to CONFIG mode
-        self.write_register(0x3D, 0x00)
-        time.sleep(0.05)
-        # Set power mode to Normal
-        self.write_register(0x3E, 0x00)
-        # Set to NDOF mode
-        self.write_register(0x3D, 0x0C)
-        time.sleep(0.5)
-
-    def read_euler_angles(self):
-        data = self.read_register(0x1A, 6)
-        yaw = (data[1] << 8) | data[0]
-        roll = (data[3] << 8) | data[2]
-        pitch = (data[5] << 8) | data[4]
-        yaw = yaw if yaw < 32768 else yaw - 65536
-        roll = roll if roll < 32768 else roll - 65536
-        pitch = pitch if pitch < 32768 else pitch - 65536
-        yaw = yaw / 16.0
-        roll = roll / 16.0
-        pitch = pitch / 16.0
-        return yaw, pitch, roll
-
-    def timer_callback(self):
-        yaw, pitch, roll = self.read_euler_angles()
-        imu_msg = Imu()
-        imu_msg.header.stamp = self.get_clock().now().to_msg()
-        imu_msg.header.frame_id = 'imu_link'
-        # Convert degrees to radians
-        yaw_rad = -(math.radians(yaw))
-        roll_rad = -(math.radians(pitch))
-        pitch_rad = -(math.radians(roll))
-        # Compute quaternion
-        cy = math.cos(yaw_rad * 0.5)
-        sy = math.sin(yaw_rad * 0.5)
-        cp = math.cos(pitch_rad * 0.5)
-        sp = math.sin(pitch_rad * 0.5)
-        cr = math.cos(roll_rad * 0.5)
-        sr = math.sin(roll_rad * 0.5)
-        imu_msg.orientation.w = cr * cp * cy + sr * sp * sy
-        imu_msg.orientation.x = sr * cp * cy - cr * sp * sy
-        imu_msg.orientation.y = cr * sp * cy + sr * cp * sy
-        imu_msg.orientation.z = cr * cp * sy - sr * sp * cy
-
-        imu_msg.orientation_covariance = [0.0025, 0, 0,
-                                  0, 0.0025, 0,
-                                  0, 0, 0.0025]
-        imu_msg.angular_velocity_covariance = [0.02, 0, 0,
-                                            0, 0.02, 0,
-                                            0, 0, 0.02]
-        imu_msg.linear_acceleration_covariance = [0.04, 0, 0,
-                                                0, 0.04, 0,
-                                                0, 0, 0.04]
-
-
-        self.publisher_.publish(imu_msg)
-        #self.get_logger().info(f'Publishing: Yaw={yaw:.2f}, Pitch={pitch:.2f}, Roll={roll:.2f}')
-
-def main(args=None):
-    rclpy.init(args=args)
-    bno055_publisher = BNO055Publisher()
-    rclpy.spin(bno055_publisher)
-    bno055_publisher.destroy_node()
-    rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
\ No newline at end of file
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py
deleted file mode 100644
index 25786c4a14305145926601ce96e723029b42c750..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py
+++ /dev/null
@@ -1,73 +0,0 @@
-#!/usr/bin/env python3
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Twist
-from gpiozero import PWMOutputDevice
-from time import sleep
-
-class Motor:
-    def __init__(self, node, EnaA, In1A, In2A, EnaB, In1B, In2B):
-        self.node = node
-        self.pwmA = PWMOutputDevice(EnaA)
-        self.in1A = PWMOutputDevice(In1A)
-        self.in2A = PWMOutputDevice(In2A)
-        self.pwmB = PWMOutputDevice(EnaB)
-        self.in1B = PWMOutputDevice(In1B)
-        self.in2B = PWMOutputDevice(In2B)
-
-    def move(self, speed=0.0, turn=0.0):
-        speed = max(-1, min(1, speed))
-        turn = max(-1, min(1, turn))
-
-        leftSpeed = speed - turn
-        rightSpeed = speed + turn
-        '''
-        left_speed = self.desired_speed - (turn_rate * self.motor.wheel_base / 2)
-        right_speed = self.desired_speed + (turn_rate * self.motor.wheel_base / 2)
-        '''
-
-        leftSpeed = max(-1, min(1, leftSpeed))
-        rightSpeed = max(-1, min(1, rightSpeed))
-
-        self.pwmA.value = abs(leftSpeed)
-        self.in1A.value = leftSpeed <=  0
-        self.in2A.value = leftSpeed > 0
-
-        self.pwmB.value = abs(rightSpeed)
-        self.in1B.value = rightSpeed > 0
-        self.in2B.value = rightSpeed <= 0
-
-        self.node.get_logger().info(f"Left Motor: Speed={leftSpeed}, Right Motor: Speed={rightSpeed}")
-
-
-    def stop(self):
-        self.pwmA.value = 0
-        self.pwmB.value = 0
-
-class MotorControlNode(Node):
-    def __init__(self):
-        super().__init__('motor_control_node')
-        self.get_logger().info("hello")
-        self.motor = Motor(self, 14, 15, 18, 17, 22, 27)
-        self.subscription = self.create_subscription(
-            Twist,
-            'cmd_vel',
-            self.cmd_vel_callback,
-            10
-        )
-
-    def cmd_vel_callback(self, msg):
-        linear_x = msg.linear.x
-        angular_z = msg.angular.z
-        self.motor.move(speed=linear_x, turn=angular_z)
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = MotorControlNode()
-    rclpy.spin(node)
-    rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
-
-#colcon build --symlink-install
\ No newline at end of file
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py
deleted file mode 100644
index 64c4d16fdc9953aae6337abffe5aa4ee71bc24dc..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py
+++ /dev/null
@@ -1,316 +0,0 @@
-import json
-import os
-import time
-import numpy as np
-from scipy.optimize import least_squares
-from geometry_msgs.msg import Point
-import rclpy
-from rclpy.node import Node
-from std_msgs.msg import String
-from sensor_msgs.msg import Imu
-import tf_transformations
-
-class SerialBuffer:
-    def __init__(self, port):
-        import serial
-        self.ser = serial.Serial(port, 115200, timeout=1)
-
-    def readFromDevice(self, expectedLines=1):
-        lines = []
-        while len(lines) < expectedLines:
-            if self.ser.in_waiting:
-                line = self.ser.readline().decode().strip()
-                if line:
-                    lines.append(line)
-            else:
-                time.sleep(0.01)
-        return lines
-
-    def getBeaconPositioningDistances(self):
-        # return [302, 463, 286, 304, 418, 328]
-        self.writeToDevice("bpm")
-        buffer = self.readFromDevice(1)[0]
-        values = list(map(float, buffer.split(" ")))
-        
-        return values
-
-    def getRangingDistances(self):
-        
-        self.writeToDevice("rng")
-        lines = self.readFromDevice(2)
-
-        print(lines)
-        distances = []
-        distances.append(list(map(float, lines[0][1:].split(" "))))
-        if lines[1] != "1":
-           distances.append(list(map(float, lines[1][1:].split(" "))))
-        else:
-            distances.append(None)
-        return distances
-
-    def writeToDevice(self, value):
-        self.ser.write((value + "\n").encode())
-
-    def __del__(self):
-        self.ser.close()
-
-class UWBNode(Node):
-    def __init__(self):
-        super().__init__('uwb_navigation_node')
-
-        self.publisher = self.create_publisher(Point, '/tag1_location', 10)
-        self.subscription = self.create_subscription(String, '/nav_command', self.handle_nav_command, 10)
-        self.imu_subscription = self.create_subscription(Imu, '/imu', self.handle_imu, 10)
-
-        self.current_yaw = None  # Store the current IMU yaw
-        self.uwb_to_imu_offset = None  # Offset between UWB and IMU heading
-        
-        self.serial_buffer = SerialBuffer("/dev/ttyACM0")
-        self.anchors = {}
-        self.anchors_coords_known = False
-        self.previous_tag1_position = None
-        anchors_file_path = os.path.join("src", "robobin", "robobin", "graphs", "anchors.json")
-        if os.path.exists(anchors_file_path):
-            try:
-                with open(anchors_file_path, 'r') as f:
-                    anchors_data = json.load(f)
-                    self.anchors = anchors_data
-                    self.anchors_coords_known = True
-                    self.get_logger().info("Anchor coordinates loaded from anchors.json.")
-            except Exception as e:
-                self.get_logger().error(f"Failed to load anchors.json: {e}")
-                self.anchors_coords_known = False
-        else:
-            self.get_logger().warning("anchors.json not found, anchor coordinates not known.")
-            self.anchors_coords_known = False
-
-        # Timer to continuously fetch and publish positions
-        self.timer = self.create_timer(1.0, self.update_positions)
-
-    def call_bpm(self):
-        try:
-            beacon_distances = self.serial_buffer.getBeaconPositioningDistances()
-            self.get_logger().info(f"Retreived values {beacon_distances }")
-            self.determine_anchor_coords(beacon_distances)
-            self.anchors_coords_known = True
-            self.get_logger().info("Anchor coordinates determined.")
-            anchors_file_path = os.path.join("src", "robobin", "robobin", "graphs", "anchors.json")
-            try:
-                with open(anchors_file_path, 'w') as f:
-                    json.dump(self.anchors, f)
-                self.get_logger().info("Anchor coordinates saved to anchors.json.")
-
-
-                graph = {
-                    "name": "Lab 1 Extended",
-                    "nodes": [],
-                    "connections": []
-                }
-
-                # Populate nodes with anchor data
-                anchor_names = ["A1", "A2", "A3", "A4"]
-                for i, (key, coords) in enumerate(self.anchors.items()):
-                    graph["nodes"].append({"name": anchor_names[i], "x": coords[0], "y": coords[1]})
-
-                # Create a fully connected adjacency matrix (all nodes connected)
-                num_nodes = len(graph["nodes"])
-                graph["connections"] = [[True if i != j else False for j in range(num_nodes)] for i in range(num_nodes)]
-
-                # Save graph to file
-                graph_file_path = os.path.join("src", "robobin", "robobin", "graphs", "graph.json")
-                with open(graph_file_path, 'w') as f:
-                    json.dump(graph, f, indent=2)
-                self.get_logger().info("Graph saved to graph.json.")
-
-       
-            except Exception as e:
-                self.get_logger().error(f"Failed to save anchors.json: {e}")
-
-        except Exception as e:
-            self.get_logger().error(f"Failed to determine anchors: {e}")
-
-    def handle_imu(self, msg):
-        # Extract yaw from quaternion
-        orientation_q = msg.orientation
-        orientation_list = [orientation_q.x, orientation_q.y, orientation_q.z, orientation_q.w]
-        _, _, yaw = tf_transformations.euler_from_quaternion(orientation_list)
-        
-        self.current_yaw = yaw  # Update current yaw
-        self.get_logger().info(f"IMU Yaw: {yaw:.2f} radians")
-    def determine_anchor_coords(self, measured_distances):
-        measured_distances = np.array(measured_distances)
-
-        initial_guess = [120, 100, 150, 200, 50]
-        bounds = ([0, 0, 0, 0, 0], [1000, 1000, 1000, 1000, 1000])
-
-        def error_function(variables, measured):
-            x_B, y_B, x_C, y_C, y_A = variables
-            a_calc = np.sqrt((x_B - 0)**2 + (y_B - y_A)**2)  # A-B
-            b_calc = np.sqrt((x_C - x_B)**2 + (y_C - y_B)**2)  # B-C
-            c_calc = np.sqrt(x_C**2 + y_C**2)  # C-D
-            d_calc = y_A  # A-D
-            e_calc = np.sqrt(x_C**2 + (y_C - y_A)**2)  # A-C
-            f_calc = np.sqrt(x_B**2 + y_B**2)  # B-D
-
-            return [
-                a_calc - measured[0],
-                b_calc - measured[3],
-                c_calc - measured[5],
-                d_calc - measured[2],
-                e_calc - measured[1],
-                f_calc - measured[4]
-            ]
-
-        result = least_squares(
-            error_function,
-            initial_guess,
-            args=(measured_distances,),
-            bounds=bounds,
-            loss='soft_l1'
-        )
-        x_B, y_B, x_C, y_C, y_A = result.x
-        self.anchors = {
-            "A1": (0, y_A),
-            "A2": (x_B, y_B),
-            "A3": (x_C, y_C),
-            "A4": (0, 0)
-        }
-
-    def calculate_tag_coordinates(self, tag_distances):
-        # self.get_logger().info(f"Tag distances: {tag_distances}")
-        if not self.anchors_coords_known or len(self.anchors) < 3:
-            self.get_logger().warning("Anchor coordinates not known.")
-            return None
-        
-        available_beacons = []
-        available_distances = []
-
-        for key, dist in tag_distances.items():
-            if dist > 0:
-                available_distances.append(dist)
-                available_beacons.append(self.anchors[key])
-
-        if len(available_beacons) < 3:
-            return None
-
-        def error_function(vars):
-            x, y = vars
-            residuals = []
-            for (bx, by), d_measured in zip(available_beacons, available_distances):
-                d_computed = np.sqrt((x - bx)**2 + (y - by)**2)
-                residuals.append(d_computed - d_measured)
-            return residuals
-
-        beacon_xs = [b[0] for b in available_beacons]
-        beacon_ys = [b[1] for b in available_beacons]
-        initial_guess = [np.mean(beacon_xs), np.mean(beacon_ys)]
-
-        bounds = (
-            [min(beacon_xs) - 100, min(beacon_ys) - 100],
-            [max(beacon_xs) + 100, max(beacon_ys) + 100]
-        )
-
-        result = least_squares(error_function, initial_guess, bounds=bounds, loss='soft_l1')
-        self.get_logger().info(f"Optimization result: {result.x}")
-        return tuple(result.x)
-
-    def update_positions(self):
-        self.get_logger().info("Updating positions...")
-        #self.get_logger().info(f"Is anchor coords known: {self.anchors_coords_known}")
-        if self.anchors_coords_known:
-            
-            
-
-            try:
-                ranging_distances = self.serial_buffer.getRangingDistances()
-                self.get_logger().info(f"Ranging Distances {ranging_distances}")
-                tag1_distances = ranging_distances[0]
-                self.get_logger().info(f"Tag1 distances {tag1_distances}")
-                tag_distances_dict = {
-                    "A1": tag1_distances[0],
-                    "A2": tag1_distances[1],
-                    "A3": tag1_distances[2],
-                    "A4": tag1_distances[3]
-                }
-                self.get_logger().info(f"Tag distances: {tag_distances_dict}")
-                tag1_position = self.calculate_tag_coordinates(tag_distances_dict)
-
-                if tag1_position is not None :
-                    self.previous_tag1_position = tag1_position
-                    position_msg = Point(x=tag1_position[0], y=tag1_position[1], z=0.0)
-                    self.publisher.publish(position_msg)
-                    #self.get_logger().info(f"Published new Tag 1 position: {tag1_position}")
-
-                #self.get_logger().info(f"Tag 1 position: {tag1_position}")
-                tag2_distances = ranging_distances[1]
-                self.get_logger().info(f"Tag2 distances {tag2_distances}")
-                tag2_position = None
-                if tag2_distances is not None:
-                    
-                    tag2_distances_dict = {
-                        "A1": tag2_distances[0],
-                        "A2": tag2_distances[1],
-                        "A3": tag2_distances[2],
-                        "A4": tag2_distances[3]
-                    }
-                    tag2_position = self.calculate_tag_coordinates(tag2_distances_dict)
-                else:
-                    self.get_logger().warning("Tag 2 is not known")
-      
-
-                # Calculate angle between tag1 and tag2, then print out the angle. @TODO: Move the bin forward to see which direction we are facing, then match the angle with the IMU yaw. This will then mean we can calculate the offset between the UWB and IMU heading.
-                if tag2_position is not None:
-                    displacement_x = tag2_position[0] - tag1_position[0]
-                    displacement_y = tag2_position[1] - tag1_position[1]
-                    
-                    # Calculate angle and distance
-                    displacement_angle = np.arctan2(displacement_y, displacement_x)  
-                    displacement_distance = np.sqrt(displacement_x**2 + displacement_y**2)
-                    
-                    self.get_logger().info(f"Displacement: dx={displacement_x:.2f}, dy={displacement_y:.2f}")
-                    self.get_logger().info(f"Displacement Angle: {np.degrees(displacement_angle):.2f}°")
-                    self.get_logger().info(f"Displacement Distance: {displacement_distance:.2f} units")
-                
-
-            except Exception as e:
-                self.get_logger().error(f"Error updating positions: {e}")
-    def clear_graph(self):
-        self.anchors_coords_known = False
-        self.anchors = {}
-        self.previous_tag1_position = None
-        graph_file_path = os.path.join("src", "robobin", "robobin", "graphs", "graph.json")
-        default_file_path = os.path.join("src", "robobin", "robobin", "graphs", "default_graph.json")
-        try:
-            with open(default_file_path, 'r') as f:
-                graph_data = json.load(f)
-                with open(graph_file_path, 'w') as f:
-                    json.dump(graph_data, f)
-        except FileNotFoundError:
-            self.get_logger().error(f"Error: File not found at {default_file_path}")
-        except json.JSONDecodeError as e:
-            self.get_logger().error(f"Error: Failed to decode JSON - {str(e)}")
-        except Exception as e:
-            self.get_logger().error(f"Error: {str(e)}")
-
-        self.get_logger().info("Graph cleared.")
-
-
-    def handle_nav_command(self, msg):
-        if msg.data == "BPM":
-            self.clear_graph()
-            self.call_bpm()
-            self.anchors_coords_known = True
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = UWBNode()
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == "__main__":
-    main()
diff --git a/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py b/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py
deleted file mode 100644
index dec8b95597d81d37e8cc8f3d74aef15b9c7702c8..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py
+++ /dev/null
@@ -1,122 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Twist, Point
-from math import sqrt, pow, atan2, radians, sin, cos
-import time
-
-
-class UWBPathingNode(Node):
-    def __init__(self):
-        super().__init__('uwb_pathing_node')
-
-        # Publisher for cmd_vel
-        self.cmd_vel_pub = self.create_publisher(Twist, '/cmd_vel', 10)
-
-        # Subscriptions
-        self.create_subscription(Point, '/start_location', self.current_location_callback, 10)
-        self.create_subscription(Point, '/target_location', self.target_location_callback, 10)
-
-        # Current and target positions
-        self.current_x = None
-        self.current_y = None
-        self.target_x = None
-        self.target_y = None
-
-        # Navigation thresholds
-        self.distance_threshold = 0.25  # meters
-        self.angle_threshold = radians(0.5)  # radians
-
-        self.kp_linear = 0.5  # Proportional gain for linear movement
-        self.kp_angular = 1.0  # Proportional gain for angular movement
-
-        self.get_logger().info('UWB Pathing Node started and waiting for positions.')
-
-    def current_location_callback(self, msg: Point):
-        """Callback to update the robot's current position."""
-        self.current_x = msg.x
-        self.current_y = msg.y
-        self.get_logger().info(f"Current Location Updated: x={self.current_x:.2f}, y={self.current_y:.2f}")
-        self.check_and_navigate()
-
-    def target_location_callback(self, msg: Point):
-        """Callback to update the target position."""
-        self.target_x = msg.x
-        self.target_y = msg.y
-        self.get_logger().info(f"Target Location Updated: x={self.target_x:.2f}, y={self.target_y:.2f}")
-        self.check_and_navigate()
-
-    def check_and_navigate(self):
-        """Check if both positions are available and navigate to the target."""
-        if self.current_x is not None and self.current_y is not None and self.target_x is not None and self.target_y is not None:
-            self.get_logger().info("Navigating to target...")
-            self.navigate_to_target()
-        else:
-            self.get_logger().warning("Waiting for both current and target positions to be available...")
-
-    def navigate_to_target(self):
-        # Ensure positions are known
-        if self.current_x is None or self.current_y is None or self.target_x is None or self.target_y is None:
-            self.get_logger().warning("Positions not fully known yet.")
-            return
-
-        # Calculate distance and angle to the target
-        displacement_x = self.target_x - self.current_x
-        displacement_y = self.target_y - self.current_y
-        distance_to_target = sqrt(pow(displacement_x, 2) + pow(displacement_y, 2))
-        angle_to_target = atan2(displacement_y, displacement_x)
-
-
-        # Check if we are close enough to the target
-        if distance_to_target <= self.distance_threshold:
-            self.stop_robot()
-            self.get_logger().info("Target reached successfully.")
-            return
-
-        # Calculate yaw error (assuming robot orientation 0 = facing x-axis)
-        # If you don't have actual orientation, you might assume the robot always faces the target directly
-        yaw_error = angle_to_target
-        yaw_error = atan2(sin(yaw_error), cos(yaw_error))  # Normalize angle
-        self.get_logger().info(f"Current Position: x={self.current_x:.2f}, y={self.current_y:.2f}")
-        self.get_logger().info(f"Target Position: x={self.target_x:.2f}, y={self.target_y:.2f}")
-        self.get_logger().info(f"Distance to Target: distance_to_target={distance_to_target:.2f} meters")
-        self.get_logger().info(f"Angle to Target: angle_to_target={angle_to_target:.2f} radians")
-        twist = Twist()
-
-        # Decide on angular velocity first
-        if abs(yaw_error) > self.angle_threshold:
-            angular_speed = self.kp_angular * abs(yaw_error)
-            twist.angular.z = angular_speed if yaw_error > 0 else -angular_speed
-            self.get_logger().info(f"Correcting Heading: yaw_error={yaw_error:.2f} radians")
-        else:
-            # Move forward when aligned with the target
-            linear_speed = self.kp_linear * distance_to_target
-            twist.linear.x = min(0.2, linear_speed)  # Limit max speed
-            self.get_logger().info(f"Moving to Target: distance={distance_to_target:.2f} meters")
-
-        # # Publish movement command
-        # self.cmd_vel_pub.publish(twist)
-
-
-    def stop_robot(self):
-        """Stops the robot by publishing zero velocities."""
-        twist = Twist()
-        self.cmd_vel_pub.publish(twist)
-        time.sleep(0.5)
-        self.get_logger().info("Robot stopped.")
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = UWBPathingNode()
-
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/install/robobin/lib/robobin/api_node b/ros2/install/robobin/lib/robobin/api_node
deleted file mode 100755
index cc9aa893d2ea34ec9802860d33c3ecbc56f32a66..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/robobin/api_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','api_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'api_node')())
diff --git a/ros2/install/robobin/lib/robobin/control_feedback b/ros2/install/robobin/lib/robobin/control_feedback
deleted file mode 100755
index fda03c810291522627cacd9263254ea54c5705b5..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/robobin/control_feedback
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','control_feedback'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'control_feedback')())
diff --git a/ros2/install/robobin/lib/robobin/encoder_node b/ros2/install/robobin/lib/robobin/encoder_node
deleted file mode 100755
index 306c64070042eb370951600e68701d23352722b4..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/robobin/encoder_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','encoder_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'encoder_node')())
diff --git a/ros2/install/robobin/lib/robobin/imu_node b/ros2/install/robobin/lib/robobin/imu_node
deleted file mode 100755
index ba00b16aab896a2cdb713ee4fc9fc13897dad633..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/robobin/imu_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','imu_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'imu_node')())
diff --git a/ros2/install/robobin/lib/robobin/motor_control_node b/ros2/install/robobin/lib/robobin/motor_control_node
deleted file mode 100755
index 42f4d86bd72336858400a8581eaf43f0276200ab..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/robobin/motor_control_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','motor_control_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'motor_control_node')())
diff --git a/ros2/install/robobin/lib/robobin/motor_node b/ros2/install/robobin/lib/robobin/motor_node
deleted file mode 100755
index 0fbb76f54aae5725259f9f5982e9bea57211b1b9..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/robobin/motor_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','motor_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'motor_node')())
diff --git a/ros2/install/robobin/lib/robobin/uwb_navigation_node b/ros2/install/robobin/lib/robobin/uwb_navigation_node
deleted file mode 100755
index b69e2c6fd1086e7abef952dd4c84419a5ab010a7..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/robobin/uwb_navigation_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','uwb_navigation_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'uwb_navigation_node')())
diff --git a/ros2/install/robobin/lib/robobin/uwb_pathing_node b/ros2/install/robobin/lib/robobin/uwb_pathing_node
deleted file mode 100755
index 30066a0eee11b663b598252f6bd63810022ace28..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/lib/robobin/uwb_pathing_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','uwb_pathing_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'uwb_pathing_node')())
diff --git a/ros2/install/robobin/share/ament_index/resource_index/packages/robobin b/ros2/install/robobin/share/ament_index/resource_index/packages/robobin
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/install/robobin/share/colcon-core/packages/robobin b/ros2/install/robobin/share/colcon-core/packages/robobin
deleted file mode 100644
index de58d893877c68ce26089692eb0b331a8f7cca35..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/colcon-core/packages/robobin
+++ /dev/null
@@ -1 +0,0 @@
-rclpy:std_msgs
\ No newline at end of file
diff --git a/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv b/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv
deleted file mode 100644
index 79d4c95b55cb72a17c9be498c3758478e2c7bb8d..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv
+++ /dev/null
@@ -1 +0,0 @@
-prepend-non-duplicate;AMENT_PREFIX_PATH;
diff --git a/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1 b/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1
deleted file mode 100644
index 26b99975794bb42ea3d6a17150e313cbfc45fc24..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1
+++ /dev/null
@@ -1,3 +0,0 @@
-# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em
-
-colcon_prepend_unique_value AMENT_PREFIX_PATH "$env:COLCON_CURRENT_PREFIX"
diff --git a/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh b/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh
deleted file mode 100644
index f3041f688a623ea5c66e65c917bc503e5fae6dc9..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh
+++ /dev/null
@@ -1,3 +0,0 @@
-# generated from colcon_core/shell/template/hook_prepend_value.sh.em
-
-_colcon_prepend_unique_value AMENT_PREFIX_PATH "$COLCON_CURRENT_PREFIX"
diff --git a/ros2/install/robobin/share/robobin/hook/pythonpath.dsv b/ros2/install/robobin/share/robobin/hook/pythonpath.dsv
deleted file mode 100644
index c2ddcdb73d1e5f7457cdbba9133f2e8a4d250b78..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/hook/pythonpath.dsv
+++ /dev/null
@@ -1 +0,0 @@
-prepend-non-duplicate;PYTHONPATH;lib/python3.12/site-packages
diff --git a/ros2/install/robobin/share/robobin/hook/pythonpath.ps1 b/ros2/install/robobin/share/robobin/hook/pythonpath.ps1
deleted file mode 100644
index bdd69aff5ed6df188b6c51f1b7f3f79e7344a2a8..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/hook/pythonpath.ps1
+++ /dev/null
@@ -1,3 +0,0 @@
-# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em
-
-colcon_prepend_unique_value PYTHONPATH "$env:COLCON_CURRENT_PREFIX\lib/python3.12/site-packages"
diff --git a/ros2/install/robobin/share/robobin/hook/pythonpath.sh b/ros2/install/robobin/share/robobin/hook/pythonpath.sh
deleted file mode 100644
index 45388fea975bdbfb649447f4a82b390f9c4b7920..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/hook/pythonpath.sh
+++ /dev/null
@@ -1,3 +0,0 @@
-# generated from colcon_core/shell/template/hook_prepend_value.sh.em
-
-_colcon_prepend_unique_value PYTHONPATH "$COLCON_CURRENT_PREFIX/lib/python3.12/site-packages"
diff --git a/ros2/install/robobin/share/robobin/launch/__pycache__/robobin_launch.cpython-312.pyc b/ros2/install/robobin/share/robobin/launch/__pycache__/robobin_launch.cpython-312.pyc
deleted file mode 100644
index 8f655ad508c584a69afd66e477eba5e5657cadd4..0000000000000000000000000000000000000000
Binary files a/ros2/install/robobin/share/robobin/launch/__pycache__/robobin_launch.cpython-312.pyc and /dev/null differ
diff --git a/ros2/install/robobin/share/robobin/launch/robobin_launch.py b/ros2/install/robobin/share/robobin/launch/robobin_launch.py
deleted file mode 100755
index 25ba08996b53a3ffe92f00e8ab2e9db51b6be1b3..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/launch/robobin_launch.py
+++ /dev/null
@@ -1,32 +0,0 @@
-# ~/GitLab/robobin/ros2/src/robobin/launch/robobin_launch.py
-
-from launch import LaunchDescription
-from launch_ros.actions import Node
-
-def generate_launch_description():
-    return LaunchDescription([
-        Node(
-            package='robobin',
-            executable='api_node',    
-            name='api_node',
-            output='screen',
-            emulate_tty=True
-
-        ),
-       
-        Node(
-            package='robobin',
-            executable='uwb_navigation_node',    
-            name='uwb_navigation_node',
-            output='screen',
-            emulate_tty=True
-        ),
-        # Add additional nodes
-        # Example:
-        # Node(
-        #     package='robobin',
-        #     executable='connection_handler_node',  
-        #     name='connection_handler_node',
-        #     output='screen'
-        # ),
-    ])
diff --git a/ros2/install/robobin/share/robobin/launch/robobin_no_components_launch.py b/ros2/install/robobin/share/robobin/launch/robobin_no_components_launch.py
deleted file mode 100644
index cea865161157a7774fe733c787e51c92bebf4c1b..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/launch/robobin_no_components_launch.py
+++ /dev/null
@@ -1,31 +0,0 @@
-# ~/GitLab/robobin/ros2/src/robobin/launch/robobin_no_components_launch.py
-
-from launch import LaunchDescription
-from launch_ros.actions import Node
-
-def generate_launch_description():
-    return LaunchDescription([
-        Node(
-            package='robobin',
-            executable='api_node',    
-            name='api_node',
-            output='screen',
-            emulate_tty=True
-
-        ),
-       
-        Node(
-            package='robobin',
-            executable='uwb_navigation_node',    
-            name='uwb_navigation_node',
-            output='screen',
-            emulate_tty=True
-        ),
-        Node(
-            package='robobin',
-            executable='motor_control_node',    
-            name='motor_control_node',
-            output='screen',
-            emulate_tty=True
-        ),
-        ])
\ No newline at end of file
diff --git a/ros2/install/robobin/share/robobin/package.bash b/ros2/install/robobin/share/robobin/package.bash
deleted file mode 100644
index 06c2f0c093746d83cc96ef961fb7841989fbe95e..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/package.bash
+++ /dev/null
@@ -1,31 +0,0 @@
-# generated from colcon_bash/shell/template/package.bash.em
-
-# This script extends the environment for this package.
-
-# a bash script is able to determine its own path if necessary
-if [ -z "$COLCON_CURRENT_PREFIX" ]; then
-  # the prefix is two levels up from the package specific share directory
-  _colcon_package_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." > /dev/null && pwd)"
-else
-  _colcon_package_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
-fi
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-# additional arguments: arguments to the script
-_colcon_package_bash_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$@"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# source sh script of this package
-_colcon_package_bash_source_script "$_colcon_package_bash_COLCON_CURRENT_PREFIX/share/robobin/package.sh"
-
-unset _colcon_package_bash_source_script
-unset _colcon_package_bash_COLCON_CURRENT_PREFIX
diff --git a/ros2/install/robobin/share/robobin/package.dsv b/ros2/install/robobin/share/robobin/package.dsv
deleted file mode 100644
index acfa8631ecbca19ce01450ed6950bc7ea21d347d..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/package.dsv
+++ /dev/null
@@ -1,6 +0,0 @@
-source;share/robobin/hook/pythonpath.ps1
-source;share/robobin/hook/pythonpath.dsv
-source;share/robobin/hook/pythonpath.sh
-source;share/robobin/hook/ament_prefix_path.ps1
-source;share/robobin/hook/ament_prefix_path.dsv
-source;share/robobin/hook/ament_prefix_path.sh
diff --git a/ros2/install/robobin/share/robobin/package.ps1 b/ros2/install/robobin/share/robobin/package.ps1
deleted file mode 100644
index 9d07a1c1d35fdeefeac40caf0b7c0e21739c2cfc..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/package.ps1
+++ /dev/null
@@ -1,116 +0,0 @@
-# generated from colcon_powershell/shell/template/package.ps1.em
-
-# function to append a value to a variable
-# which uses colons as separators
-# duplicates as well as leading separators are avoided
-# first argument: the name of the result variable
-# second argument: the value to be prepended
-function colcon_append_unique_value {
-  param (
-    $_listname,
-    $_value
-  )
-
-  # get values from variable
-  if (Test-Path Env:$_listname) {
-    $_values=(Get-Item env:$_listname).Value
-  } else {
-    $_values=""
-  }
-  $_duplicate=""
-  # start with no values
-  $_all_values=""
-  # iterate over existing values in the variable
-  if ($_values) {
-    $_values.Split(";") | ForEach {
-      # not an empty string
-      if ($_) {
-        # not a duplicate of _value
-        if ($_ -eq $_value) {
-          $_duplicate="1"
-        }
-        if ($_all_values) {
-          $_all_values="${_all_values};$_"
-        } else {
-          $_all_values="$_"
-        }
-      }
-    }
-  }
-  # append only non-duplicates
-  if (!$_duplicate) {
-    # avoid leading separator
-    if ($_all_values) {
-      $_all_values="${_all_values};${_value}"
-    } else {
-      $_all_values="${_value}"
-    }
-  }
-
-  # export the updated variable
-  Set-Item env:\$_listname -Value "$_all_values"
-}
-
-# function to prepend a value to a variable
-# which uses colons as separators
-# duplicates as well as trailing separators are avoided
-# first argument: the name of the result variable
-# second argument: the value to be prepended
-function colcon_prepend_unique_value {
-  param (
-    $_listname,
-    $_value
-  )
-
-  # get values from variable
-  if (Test-Path Env:$_listname) {
-    $_values=(Get-Item env:$_listname).Value
-  } else {
-    $_values=""
-  }
-  # start with the new value
-  $_all_values="$_value"
-  # iterate over existing values in the variable
-  if ($_values) {
-    $_values.Split(";") | ForEach {
-      # not an empty string
-      if ($_) {
-        # not a duplicate of _value
-        if ($_ -ne $_value) {
-          # keep non-duplicate values
-          $_all_values="${_all_values};$_"
-        }
-      }
-    }
-  }
-  # export the updated variable
-  Set-Item env:\$_listname -Value "$_all_values"
-}
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-# additional arguments: arguments to the script
-function colcon_package_source_powershell_script {
-  param (
-    $_colcon_package_source_powershell_script
-  )
-  # source script with conditional trace output
-  if (Test-Path $_colcon_package_source_powershell_script) {
-    if ($env:COLCON_TRACE) {
-      echo ". '$_colcon_package_source_powershell_script'"
-    }
-    . "$_colcon_package_source_powershell_script"
-  } else {
-    Write-Error "not found: '$_colcon_package_source_powershell_script'"
-  }
-}
-
-
-# a powershell script is able to determine its own path
-# the prefix is two levels up from the package specific share directory
-$env:COLCON_CURRENT_PREFIX=(Get-Item $PSCommandPath).Directory.Parent.Parent.FullName
-
-colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/robobin/hook/pythonpath.ps1"
-colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/robobin/hook/ament_prefix_path.ps1"
-
-Remove-Item Env:\COLCON_CURRENT_PREFIX
diff --git a/ros2/install/robobin/share/robobin/package.sh b/ros2/install/robobin/share/robobin/package.sh
deleted file mode 100644
index 4ee71b1eec75c9faf6cc11ad228edd72c14e0c11..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/package.sh
+++ /dev/null
@@ -1,87 +0,0 @@
-# generated from colcon_core/shell/template/package.sh.em
-
-# This script extends the environment for this package.
-
-# function to prepend a value to a variable
-# which uses colons as separators
-# duplicates as well as trailing separators are avoided
-# first argument: the name of the result variable
-# second argument: the value to be prepended
-_colcon_prepend_unique_value() {
-  # arguments
-  _listname="$1"
-  _value="$2"
-
-  # get values from variable
-  eval _values=\"\$$_listname\"
-  # backup the field separator
-  _colcon_prepend_unique_value_IFS=$IFS
-  IFS=":"
-  # start with the new value
-  _all_values="$_value"
-  # workaround SH_WORD_SPLIT not being set in zsh
-  if [ "$(command -v colcon_zsh_convert_to_array)" ]; then
-    colcon_zsh_convert_to_array _values
-  fi
-  # iterate over existing values in the variable
-  for _item in $_values; do
-    # ignore empty strings
-    if [ -z "$_item" ]; then
-      continue
-    fi
-    # ignore duplicates of _value
-    if [ "$_item" = "$_value" ]; then
-      continue
-    fi
-    # keep non-duplicate values
-    _all_values="$_all_values:$_item"
-  done
-  unset _item
-  # restore the field separator
-  IFS=$_colcon_prepend_unique_value_IFS
-  unset _colcon_prepend_unique_value_IFS
-  # export the updated variable
-  eval export $_listname=\"$_all_values\"
-  unset _all_values
-  unset _values
-
-  unset _value
-  unset _listname
-}
-
-# since a plain shell script can't determine its own path when being sourced
-# either use the provided COLCON_CURRENT_PREFIX
-# or fall back to the build time prefix (if it exists)
-_colcon_package_sh_COLCON_CURRENT_PREFIX="/home/robobin/robobin/ros2/install/robobin"
-if [ -z "$COLCON_CURRENT_PREFIX" ]; then
-  if [ ! -d "$_colcon_package_sh_COLCON_CURRENT_PREFIX" ]; then
-    echo "The build time path \"$_colcon_package_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2
-    unset _colcon_package_sh_COLCON_CURRENT_PREFIX
-    return 1
-  fi
-  COLCON_CURRENT_PREFIX="$_colcon_package_sh_COLCON_CURRENT_PREFIX"
-fi
-unset _colcon_package_sh_COLCON_CURRENT_PREFIX
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-# additional arguments: arguments to the script
-_colcon_package_sh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$@"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# source sh hooks
-_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/robobin/hook/pythonpath.sh"
-_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/robobin/hook/ament_prefix_path.sh"
-
-unset _colcon_package_sh_source_script
-unset COLCON_CURRENT_PREFIX
-
-# do not unset _colcon_prepend_unique_value since it might be used by non-primary shell hooks
diff --git a/ros2/install/robobin/share/robobin/package.xml b/ros2/install/robobin/share/robobin/package.xml
deleted file mode 100644
index fd694d6dfcde24970ee00ec057ad19c1b21a15cc..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/package.xml
+++ /dev/null
@@ -1,21 +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>robobin</name>
-  <version>0.0.0</version>
-  <description>TODO: Package description</description>
-  <maintainer email="plw1g21@soton.ac.uk">paulw</maintainer>
-  <license>TODO: License declaration</license>
-
-  <depend>rclpy</depend>
-  <depend>std_msgs</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/ros2/install/robobin/share/robobin/package.zsh b/ros2/install/robobin/share/robobin/package.zsh
deleted file mode 100644
index a6a5cc52558a9b09650fee9244a52203c590836d..0000000000000000000000000000000000000000
--- a/ros2/install/robobin/share/robobin/package.zsh
+++ /dev/null
@@ -1,42 +0,0 @@
-# generated from colcon_zsh/shell/template/package.zsh.em
-
-# This script extends the environment for this package.
-
-# a zsh script is able to determine its own path if necessary
-if [ -z "$COLCON_CURRENT_PREFIX" ]; then
-  # the prefix is two levels up from the package specific share directory
-  _colcon_package_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd)"
-else
-  _colcon_package_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
-fi
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-# additional arguments: arguments to the script
-_colcon_package_zsh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$@"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# function to convert array-like strings into arrays
-# to workaround SH_WORD_SPLIT not being set
-colcon_zsh_convert_to_array() {
-  local _listname=$1
-  local _dollar="$"
-  local _split="{="
-  local _to_array="(\"$_dollar$_split$_listname}\")"
-  eval $_listname=$_to_array
-}
-
-# source sh script of this package
-_colcon_package_zsh_source_script "$_colcon_package_zsh_COLCON_CURRENT_PREFIX/share/robobin/package.sh"
-unset convert_zsh_to_array
-
-unset _colcon_package_zsh_source_script
-unset _colcon_package_zsh_COLCON_CURRENT_PREFIX
diff --git a/ros2/install/setup.bash b/ros2/install/setup.bash
deleted file mode 100644
index 42f8331062dbdb5760cc2e907f6e5a85464fb43f..0000000000000000000000000000000000000000
--- a/ros2/install/setup.bash
+++ /dev/null
@@ -1,37 +0,0 @@
-# generated from colcon_bash/shell/template/prefix_chain.bash.em
-
-# This script extends the environment with the environment of other prefix
-# paths which were sourced when this file was generated as well as all packages
-# contained in this prefix path.
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-_colcon_prefix_chain_bash_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$1"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# source chained prefixes
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="/opt/ros/jazzy"
-_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="/home/robobin/Robobin_Project/ros2/robobin_main/install"
-_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="/home/robobin/robobin/ros2/src/install"
-_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
-
-# source this prefix
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)"
-_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
-
-unset COLCON_CURRENT_PREFIX
-unset _colcon_prefix_chain_bash_source_script
diff --git a/ros2/install/setup.ps1 b/ros2/install/setup.ps1
deleted file mode 100644
index b180217314a3179a2b4dd061eded2d712106e28d..0000000000000000000000000000000000000000
--- a/ros2/install/setup.ps1
+++ /dev/null
@@ -1,31 +0,0 @@
-# generated from colcon_powershell/shell/template/prefix_chain.ps1.em
-
-# This script extends the environment with the environment of other prefix
-# paths which were sourced when this file was generated as well as all packages
-# contained in this prefix path.
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-function _colcon_prefix_chain_powershell_source_script {
-  param (
-    $_colcon_prefix_chain_powershell_source_script_param
-  )
-  # source script with conditional trace output
-  if (Test-Path $_colcon_prefix_chain_powershell_source_script_param) {
-    if ($env:COLCON_TRACE) {
-      echo ". '$_colcon_prefix_chain_powershell_source_script_param'"
-    }
-    . "$_colcon_prefix_chain_powershell_source_script_param"
-  } else {
-    Write-Error "not found: '$_colcon_prefix_chain_powershell_source_script_param'"
-  }
-}
-
-# source chained prefixes
-_colcon_prefix_chain_powershell_source_script "/opt/ros/jazzy\local_setup.ps1"
-_colcon_prefix_chain_powershell_source_script "/home/robobin/Robobin_Project/ros2/robobin_main/install\local_setup.ps1"
-_colcon_prefix_chain_powershell_source_script "/home/robobin/robobin/ros2/src/install\local_setup.ps1"
-
-# source this prefix
-$env:COLCON_CURRENT_PREFIX=(Split-Path $PSCommandPath -Parent)
-_colcon_prefix_chain_powershell_source_script "$env:COLCON_CURRENT_PREFIX\local_setup.ps1"
diff --git a/ros2/install/setup.sh b/ros2/install/setup.sh
deleted file mode 100644
index 85a14d324a38abddb7305664e4b90efa1e5538ff..0000000000000000000000000000000000000000
--- a/ros2/install/setup.sh
+++ /dev/null
@@ -1,53 +0,0 @@
-# generated from colcon_core/shell/template/prefix_chain.sh.em
-
-# This script extends the environment with the environment of other prefix
-# paths which were sourced when this file was generated as well as all packages
-# contained in this prefix path.
-
-# since a plain shell script can't determine its own path when being sourced
-# either use the provided COLCON_CURRENT_PREFIX
-# or fall back to the build time prefix (if it exists)
-_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX=/home/robobin/robobin/ros2/install
-if [ ! -z "$COLCON_CURRENT_PREFIX" ]; then
-  _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
-elif [ ! -d "$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX" ]; then
-  echo "The build time path \"$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2
-  unset _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX
-  return 1
-fi
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-_colcon_prefix_chain_sh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$1"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# source chained prefixes
-# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
-COLCON_CURRENT_PREFIX="/opt/ros/jazzy"
-_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
-
-# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
-COLCON_CURRENT_PREFIX="/home/robobin/Robobin_Project/ros2/robobin_main/install"
-_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
-
-# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
-COLCON_CURRENT_PREFIX="/home/robobin/robobin/ros2/src/install"
-_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
-
-
-# source this prefix
-# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
-COLCON_CURRENT_PREFIX="$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX"
-_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
-
-unset _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX
-unset _colcon_prefix_chain_sh_source_script
-unset COLCON_CURRENT_PREFIX
diff --git a/ros2/install/setup.zsh b/ros2/install/setup.zsh
deleted file mode 100644
index 927b2dcaf80ffd4a156c9a045cd5ba8bd059e460..0000000000000000000000000000000000000000
--- a/ros2/install/setup.zsh
+++ /dev/null
@@ -1,37 +0,0 @@
-# generated from colcon_zsh/shell/template/prefix_chain.zsh.em
-
-# This script extends the environment with the environment of other prefix
-# paths which were sourced when this file was generated as well as all packages
-# contained in this prefix path.
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-_colcon_prefix_chain_zsh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$1"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# source chained prefixes
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="/opt/ros/jazzy"
-_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="/home/robobin/Robobin_Project/ros2/robobin_main/install"
-_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="/home/robobin/robobin/ros2/src/install"
-_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
-
-# source this prefix
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)"
-_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
-
-unset COLCON_CURRENT_PREFIX
-unset _colcon_prefix_chain_zsh_source_script
diff --git a/ros2/log/COLCON_IGNORE b/ros2/log/COLCON_IGNORE
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_14-46-24/events.log b/ros2/log/build_2024-12-16_14-46-24/events.log
deleted file mode 100644
index 3d255709afe395d7d4b28588883144769fa8c899..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-46-24/events.log
+++ /dev/null
@@ -1,84 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000283] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.001538] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099672] (-) TimerEvent: {}
-[0.199984] (-) TimerEvent: {}
-[0.300281] (-) TimerEvent: {}
-[0.400607] (-) TimerEvent: {}
-[0.500920] (-) TimerEvent: {}
-[0.601214] (-) TimerEvent: {}
-[0.701500] (-) TimerEvent: {}
-[0.801792] (-) TimerEvent: {}
-[0.902092] (-) TimerEvent: {}
-[1.002413] (-) TimerEvent: {}
-[1.102702] (-) TimerEvent: {}
-[1.203046] (-) TimerEvent: {}
-[1.288355] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'SYSTEMD_EXEC_PID': '1626', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/session.slice/org.gnome.Shell@wayland.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1593,unix/robobin-desktop:/tmp/.ICE-unix/1593', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/7b90321a_ecc9_49c1_97ef_e4cec503a50b', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.OOYBZ2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.110', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.303124] (-) TimerEvent: {}
-[1.403432] (-) TimerEvent: {}
-[1.503728] (-) TimerEvent: {}
-[1.604028] (-) TimerEvent: {}
-[1.678791] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.679294] (robobin) StdoutLine: {'line': b'creating ../../build/robobin/robobin.egg-info\n'}
-[1.704088] (-) TimerEvent: {}
-[1.706127] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.707352] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.707761] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.708010] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.708144] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[1.708358] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.763886] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.764791] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.765010] (robobin) StdoutLine: {'line': b'running build\n'}
-[1.765113] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[1.765303] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/build/robobin/build\n'}
-[1.765403] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/build/robobin/build/lib\n'}
-[1.765525] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.765633] (robobin) StdoutLine: {'line': b'copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.767241] (robobin) StdoutLine: {'line': b'copying robobin/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.767391] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.767575] (robobin) StdoutLine: {'line': b'copying robobin/api_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.768331] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers\n'}
-[1.768458] (robobin) StdoutLine: {'line': b'copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers\n'}
-[1.768953] (robobin) StdoutLine: {'line': b'copying robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers\n'}
-[1.769086] (robobin) StdoutLine: {'line': b'copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers\n'}
-[1.769754] (robobin) StdoutLine: {'line': b'running install\n'}
-[1.779595] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[1.804157] (-) TimerEvent: {}
-[1.810160] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.810748] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.811008] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.811331] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.811777] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.811960] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.812304] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.812553] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.812802] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.813935] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc\n'}
-[1.815265] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__init__.py to __init__.cpython-312.pyc\n'}
-[1.815549] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[1.819797] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc\n'}
-[1.821893] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py to __init__.cpython-312.pyc\n'}
-[1.822177] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc\n'}
-[1.823359] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc\n'}
-[1.824691] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[1.824837] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/install/robobin/share/ament_index\n'}
-[1.824938] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index\n'}
-[1.825075] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages\n'}
-[1.825211] (robobin) StdoutLine: {'line': b'copying resource/robobin -> /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages\n'}
-[1.825371] (robobin) StdoutLine: {'line': b'copying package.xml -> /home/robobin/robobin/ros2/install/robobin/share/robobin\n'}
-[1.825552] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/install/robobin/share/robobin/launch\n'}
-[1.825662] (robobin) StdoutLine: {'line': b'copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch\n'}
-[1.826387] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[1.855659] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[1.856875] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[1.904234] (-) TimerEvent: {}
-[2.004480] (-) TimerEvent: {}
-[2.054439] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.054704] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.054836] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.055350] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.104592] (-) TimerEvent: {}
-[2.145646] (robobin) CommandEnded: {'returncode': 0}
-[2.157828] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.159336] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-16_14-46-24/logger_all.log b/ros2/log/build_2024-12-16_14-46-24/logger_all.log
deleted file mode 100644
index 65c2e5343df18edb9550cf04adf7674627f775a8..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-46-24/logger_all.log
+++ /dev/null
@@ -1,138 +0,0 @@
-[0.151s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.151s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffffada6d220>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffffada6cf50>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffffada6cf50>>, mixin_verb=('build',))
-[0.207s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.207s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.207s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.207s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.207s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.207s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.208s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.208s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.208s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.208s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.208s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.208s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.208s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.208s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.208s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.208s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.253s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.253s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.253s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.253s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.253s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.253s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.277s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.277s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.278s] WARNING:colcon.colcon_ros.prefix_path.ament:The path '/home/robobin/robobin/ros2/install/robobin' in the environment variable AMENT_PREFIX_PATH doesn't exist
-[0.280s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 0 installed packages in /home/robobin/robobin/ros2/install
-[0.281s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.284s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.289s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.355s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.355s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.355s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.356s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.356s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.356s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.356s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.356s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.356s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.356s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.356s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.357s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.358s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.358s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.364s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.364s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.366s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.368s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.370s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.370s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.729s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.729s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.729s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.649s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.503s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.506s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.506s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.507s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.507s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.507s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.508s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.508s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.508s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.509s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.509s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.510s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.510s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.510s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.511s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.512s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.512s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.513s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.514s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.515s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.515s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.515s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.515s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.530s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.530s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.530s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.555s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.555s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.556s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.558s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.560s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[2.561s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[2.562s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[2.563s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[2.564s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[2.565s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[2.566s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-16_14-46-24/robobin/command.log b/ros2/log/build_2024-12-16_14-46-24/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-46-24/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_14-46-24/robobin/stderr.log b/ros2/log/build_2024-12-16_14-46-24/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_14-46-24/robobin/stdout.log b/ros2/log/build_2024-12-16_14-46-24/robobin/stdout.log
deleted file mode 100644
index 41f4d9d0dc7e6637df3cae20909fe6f17fdbc300..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-46-24/robobin/stdout.log
+++ /dev/null
@@ -1,56 +0,0 @@
-running egg_info
-creating ../../build/robobin/robobin.egg-info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-creating /home/robobin/robobin/ros2/build/robobin/build
-creating /home/robobin/robobin/ros2/build/robobin/build/lib
-creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/api_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-running install
-running install_lib
-creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__init__.py to __init__.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py to __init__.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc
-running install_data
-creating /home/robobin/robobin/ros2/install/robobin/share/ament_index
-creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index
-creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages
-copying resource/robobin -> /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages
-copying package.xml -> /home/robobin/robobin/ros2/install/robobin/share/robobin
-creating /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-running install_egg_info
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_14-46-24/robobin/stdout_stderr.log b/ros2/log/build_2024-12-16_14-46-24/robobin/stdout_stderr.log
deleted file mode 100644
index 41f4d9d0dc7e6637df3cae20909fe6f17fdbc300..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-46-24/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,56 +0,0 @@
-running egg_info
-creating ../../build/robobin/robobin.egg-info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-creating /home/robobin/robobin/ros2/build/robobin/build
-creating /home/robobin/robobin/ros2/build/robobin/build/lib
-creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/api_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-running install
-running install_lib
-creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__init__.py to __init__.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py to __init__.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc
-running install_data
-creating /home/robobin/robobin/ros2/install/robobin/share/ament_index
-creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index
-creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages
-copying resource/robobin -> /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages
-copying package.xml -> /home/robobin/robobin/ros2/install/robobin/share/robobin
-creating /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-running install_egg_info
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_14-46-24/robobin/streams.log b/ros2/log/build_2024-12-16_14-46-24/robobin/streams.log
deleted file mode 100644
index 95b229133364c2e2f90d23505a6b2496f9431298..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-46-24/robobin/streams.log
+++ /dev/null
@@ -1,58 +0,0 @@
-[1.289s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[1.677s] running egg_info
-[1.677s] creating ../../build/robobin/robobin.egg-info
-[1.704s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[1.705s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[1.705s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[1.706s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[1.706s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[1.706s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.762s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.762s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.763s] running build
-[1.763s] running build_py
-[1.763s] creating /home/robobin/robobin/ros2/build/robobin/build
-[1.763s] creating /home/robobin/robobin/ros2/build/robobin/build/lib
-[1.763s] creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.763s] copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.765s] copying robobin/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.765s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.765s] copying robobin/api_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.766s] creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-[1.766s] copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-[1.767s] copying robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-[1.767s] copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-[1.767s] running install
-[1.777s] running install_lib
-[1.808s] creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.808s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.809s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.809s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.809s] creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.810s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.810s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.810s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.810s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.812s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc
-[1.813s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__init__.py to __init__.cpython-312.pyc
-[1.813s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[1.817s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc
-[1.819s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py to __init__.cpython-312.pyc
-[1.820s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc
-[1.821s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc
-[1.822s] running install_data
-[1.822s] creating /home/robobin/robobin/ros2/install/robobin/share/ament_index
-[1.823s] creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index
-[1.823s] creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages
-[1.823s] copying resource/robobin -> /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages
-[1.823s] copying package.xml -> /home/robobin/robobin/ros2/install/robobin/share/robobin
-[1.823s] creating /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-[1.823s] copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-[1.824s] running install_egg_info
-[1.853s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[1.854s] running install_scripts
-[2.052s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.052s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.052s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.053s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.144s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_14-56-59/events.log b/ros2/log/build_2024-12-16_14-56-59/events.log
deleted file mode 100644
index 840e319fd6affd6a90c9012b83ca85101dcb67c1..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-56-59/events.log
+++ /dev/null
@@ -1,58 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.001180] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.002674] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099650] (-) TimerEvent: {}
-[0.200085] (-) TimerEvent: {}
-[0.300409] (-) TimerEvent: {}
-[0.400834] (-) TimerEvent: {}
-[0.503598] (-) TimerEvent: {}
-[0.605394] (-) TimerEvent: {}
-[0.708333] (-) TimerEvent: {}
-[0.809115] (-) TimerEvent: {}
-[0.909505] (-) TimerEvent: {}
-[1.010043] (-) TimerEvent: {}
-[1.110487] (-) TimerEvent: {}
-[1.211016] (-) TimerEvent: {}
-[1.311421] (-) TimerEvent: {}
-[1.411816] (-) TimerEvent: {}
-[1.512251] (-) TimerEvent: {}
-[1.612626] (-) TimerEvent: {}
-[1.698394] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'SYSTEMD_EXEC_PID': '1626', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/session.slice/org.gnome.Shell@wayland.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1593,unix/robobin-desktop:/tmp/.ICE-unix/1593', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/ea7f1a2b_3a39_4f21_8a31_dd3a276c0cc6', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.OOYBZ2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.110', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.712812] (-) TimerEvent: {}
-[1.813317] (-) TimerEvent: {}
-[1.913789] (-) TimerEvent: {}
-[2.014227] (-) TimerEvent: {}
-[2.114645] (-) TimerEvent: {}
-[2.194028] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[2.214748] (-) TimerEvent: {}
-[2.226902] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[2.228183] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[2.229062] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[2.229865] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[2.231087] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.301555] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.302924] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.303810] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.303996] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.305089] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[2.305256] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.314899] (-) TimerEvent: {}
-[2.315852] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.351510] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.353807] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.360979] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.361263] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.393013] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.396808] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.397075] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.415061] (-) TimerEvent: {}
-[2.515641] (-) TimerEvent: {}
-[2.616376] (-) TimerEvent: {}
-[2.650367] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.650767] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.651851] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.653021] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.716536] (-) TimerEvent: {}
-[2.763964] (robobin) CommandEnded: {'returncode': 0}
-[2.783959] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.787482] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-16_14-56-59/logger_all.log b/ros2/log/build_2024-12-16_14-56-59/logger_all.log
deleted file mode 100644
index 9bda2ccb336c36509c4fa6a9afae23269f1d25c5..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-56-59/logger_all.log
+++ /dev/null
@@ -1,136 +0,0 @@
-[0.178s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.178s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffffbd92d610>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffffbd92d310>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffffbd92d310>>, mixin_verb=('build',))
-[0.243s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.243s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.243s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.243s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.243s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.243s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.243s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.294s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.294s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.294s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.294s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.294s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.294s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.294s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.295s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.296s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.297s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.297s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.297s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.297s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.297s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.297s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.297s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.297s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.297s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.302s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.302s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.302s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.302s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.302s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.302s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.330s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.331s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.335s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.337s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.341s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.415s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.415s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.415s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.415s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.415s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.415s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.415s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.415s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.415s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.415s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.416s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.417s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.418s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.418s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.426s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.426s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.430s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.432s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.435s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.435s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.869s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.869s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.869s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[2.117s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[3.181s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[3.185s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[3.185s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[3.187s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[3.187s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[3.187s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[3.188s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[3.188s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[3.188s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[3.189s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[3.190s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[3.191s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[3.191s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[3.191s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[3.193s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[3.194s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[3.195s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[3.196s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[3.198s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[3.201s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[3.204s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[3.204s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[3.204s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[3.226s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[3.226s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[3.226s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[3.256s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[3.256s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[3.258s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[3.261s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[3.263s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[3.265s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[3.266s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[3.269s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[3.270s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[3.272s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[3.274s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-16_14-56-59/robobin/command.log b/ros2/log/build_2024-12-16_14-56-59/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-56-59/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_14-56-59/robobin/stderr.log b/ros2/log/build_2024-12-16_14-56-59/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_14-56-59/robobin/stdout.log b/ros2/log/build_2024-12-16_14-56-59/robobin/stdout.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-56-59/robobin/stdout.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_14-56-59/robobin/stdout_stderr.log b/ros2/log/build_2024-12-16_14-56-59/robobin/stdout_stderr.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-56-59/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_14-56-59/robobin/streams.log b/ros2/log/build_2024-12-16_14-56-59/robobin/streams.log
deleted file mode 100644
index d143e8dd8fc010a893fdb9010980f00f3c2ea983..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-56-59/robobin/streams.log
+++ /dev/null
@@ -1,26 +0,0 @@
-[1.696s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.191s] running egg_info
-[2.223s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[2.225s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[2.225s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[2.226s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[2.227s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[2.298s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.299s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.300s] running build
-[2.300s] running build_py
-[2.301s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[2.301s] running install
-[2.312s] running install_lib
-[2.348s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[2.350s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.357s] running install_data
-[2.357s] running install_egg_info
-[2.389s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.393s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.393s] running install_scripts
-[2.647s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.647s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.648s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.649s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.760s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_14-58-14/events.log b/ros2/log/build_2024-12-16_14-58-14/events.log
deleted file mode 100644
index 7cc7c9597bc825c33bd9d65ce1af8cdc230f8872..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-58-14/events.log
+++ /dev/null
@@ -1,54 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000436] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.001379] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099644] (-) TimerEvent: {}
-[0.200005] (-) TimerEvent: {}
-[0.300351] (-) TimerEvent: {}
-[0.400686] (-) TimerEvent: {}
-[0.502728] (-) TimerEvent: {}
-[0.603282] (-) TimerEvent: {}
-[0.703790] (-) TimerEvent: {}
-[0.804292] (-) TimerEvent: {}
-[0.904626] (-) TimerEvent: {}
-[1.004980] (-) TimerEvent: {}
-[1.105342] (-) TimerEvent: {}
-[1.205657] (-) TimerEvent: {}
-[1.305992] (-) TimerEvent: {}
-[1.406350] (-) TimerEvent: {}
-[1.444772] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'SYSTEMD_EXEC_PID': '1626', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/session.slice/org.gnome.Shell@wayland.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1593,unix/robobin-desktop:/tmp/.ICE-unix/1593', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/ea7f1a2b_3a39_4f21_8a31_dd3a276c0cc6', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.OOYBZ2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.110', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.506484] (-) TimerEvent: {}
-[1.606888] (-) TimerEvent: {}
-[1.707250] (-) TimerEvent: {}
-[1.807582] (-) TimerEvent: {}
-[1.847501] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.874652] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.875087] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.876099] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.876748] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.877466] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[1.907686] (-) TimerEvent: {}
-[1.936512] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.937667] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.937954] (robobin) StdoutLine: {'line': b'running build\n'}
-[1.938085] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[1.938894] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.939689] (robobin) StdoutLine: {'line': b'running install\n'}
-[1.949334] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[1.977135] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.978361] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[1.983201] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[1.983424] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.007782] (-) TimerEvent: {}
-[2.017706] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.018216] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.019471] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.107892] (-) TimerEvent: {}
-[2.208248] (-) TimerEvent: {}
-[2.252039] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.252374] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.253951] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.256109] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.308408] (-) TimerEvent: {}
-[2.365512] (robobin) CommandEnded: {'returncode': 0}
-[2.380606] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.382703] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-16_14-58-14/logger_all.log b/ros2/log/build_2024-12-16_14-58-14/logger_all.log
deleted file mode 100644
index 72c401fc56117f22ee769c419aba742f3e56e8dd..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-58-14/logger_all.log
+++ /dev/null
@@ -1,137 +0,0 @@
-[0.157s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.157s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff838ad700>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff838ad3d0>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff838ad3d0>>, mixin_verb=('build',))
-[0.217s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.217s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.217s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.217s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.217s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.217s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.217s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.217s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.260s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.260s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.260s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.260s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.260s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.260s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.260s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.260s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.260s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.266s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.266s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.266s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.266s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.266s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.266s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.290s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.290s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.292s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/install
-[0.293s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.295s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.298s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.366s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.366s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.366s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.366s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.366s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.366s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.366s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.366s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.366s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.366s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.366s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.368s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.368s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.369s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.375s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.375s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.377s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.392s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.394s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.394s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.761s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.762s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.762s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.816s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.733s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.736s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.737s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.738s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.738s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.738s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.738s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.738s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.739s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.739s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.740s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.741s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.742s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.742s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.743s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.744s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.745s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.746s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.747s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.748s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.748s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.749s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.749s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.772s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.774s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.774s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.807s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.808s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.810s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.812s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.814s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[2.815s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[2.816s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[2.818s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[2.820s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[2.822s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[2.824s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-16_14-58-14/robobin/command.log b/ros2/log/build_2024-12-16_14-58-14/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-58-14/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_14-58-14/robobin/stderr.log b/ros2/log/build_2024-12-16_14-58-14/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_14-58-14/robobin/stdout.log b/ros2/log/build_2024-12-16_14-58-14/robobin/stdout.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-58-14/robobin/stdout.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_14-58-14/robobin/stdout_stderr.log b/ros2/log/build_2024-12-16_14-58-14/robobin/stdout_stderr.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-58-14/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_14-58-14/robobin/streams.log b/ros2/log/build_2024-12-16_14-58-14/robobin/streams.log
deleted file mode 100644
index 6938bca7138da8d52aae9c3312d157cb35a9e5f4..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_14-58-14/robobin/streams.log
+++ /dev/null
@@ -1,26 +0,0 @@
-[1.447s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[1.846s] running egg_info
-[1.873s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[1.873s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[1.874s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[1.875s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[1.876s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[1.935s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.936s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.936s] running build
-[1.936s] running build_py
-[1.937s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.938s] running install
-[1.948s] running install_lib
-[1.975s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.977s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[1.981s] running install_data
-[1.982s] running install_egg_info
-[2.016s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.016s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.018s] running install_scripts
-[2.250s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.251s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.252s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.254s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.364s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-00-58/events.log b/ros2/log/build_2024-12-16_15-00-58/events.log
deleted file mode 100644
index ee6a003ce23b01d50cbcfaedb607a4be2864f9fe..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-00-58/events.log
+++ /dev/null
@@ -1,56 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000312] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.001044] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099679] (-) TimerEvent: {}
-[0.200060] (-) TimerEvent: {}
-[0.300409] (-) TimerEvent: {}
-[0.400792] (-) TimerEvent: {}
-[0.501263] (-) TimerEvent: {}
-[0.601858] (-) TimerEvent: {}
-[0.702232] (-) TimerEvent: {}
-[0.802721] (-) TimerEvent: {}
-[0.903052] (-) TimerEvent: {}
-[1.003391] (-) TimerEvent: {}
-[1.103768] (-) TimerEvent: {}
-[1.204101] (-) TimerEvent: {}
-[1.304453] (-) TimerEvent: {}
-[1.404877] (-) TimerEvent: {}
-[1.469512] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'SYSTEMD_EXEC_PID': '1626', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/session.slice/org.gnome.Shell@wayland.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1593,unix/robobin-desktop:/tmp/.ICE-unix/1593', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/ea7f1a2b_3a39_4f21_8a31_dd3a276c0cc6', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.OOYBZ2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.110', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.504964] (-) TimerEvent: {}
-[1.605299] (-) TimerEvent: {}
-[1.705642] (-) TimerEvent: {}
-[1.805979] (-) TimerEvent: {}
-[1.880990] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.906050] (-) TimerEvent: {}
-[1.909005] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.909794] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.915409] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.926709] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.931479] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[1.995068] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.996232] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.996514] (robobin) StdoutLine: {'line': b'running build\n'}
-[1.996652] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[1.996920] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.997722] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.006164] (-) TimerEvent: {}
-[2.009637] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.044953] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.046237] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.051147] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.051354] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.081104] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.081626] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.082883] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.106224] (-) TimerEvent: {}
-[2.209719] (-) TimerEvent: {}
-[2.285229] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.285600] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.294325] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.303879] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.309791] (-) TimerEvent: {}
-[2.402415] (robobin) CommandEnded: {'returncode': 0}
-[2.409886] (-) TimerEvent: {}
-[2.510165] (-) TimerEvent: {}
-[2.565069] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.569470] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-16_15-00-58/logger_all.log b/ros2/log/build_2024-12-16_15-00-58/logger_all.log
deleted file mode 100644
index d91f2943e146276606566aed2a928aab78d338c6..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-00-58/logger_all.log
+++ /dev/null
@@ -1,137 +0,0 @@
-[0.155s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.155s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff8c5317c0>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff8c531490>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff8c531490>>, mixin_verb=('build',))
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.212s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.260s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.260s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.260s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.260s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.260s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.260s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.284s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.285s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.287s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/install
-[0.288s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.290s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.293s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.361s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.361s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.361s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.361s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.361s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.361s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.361s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.361s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.361s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.362s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.362s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.363s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.364s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.364s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.370s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.371s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.372s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.379s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.388s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.388s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.770s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.770s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.771s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.836s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.766s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.769s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.769s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.770s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.770s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.770s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.771s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.771s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.771s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.772s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.855s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.886s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.886s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.887s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.907s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.913s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.921s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.922s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.925s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.928s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.929s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.929s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.929s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.946s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.946s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.946s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.973s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.973s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.975s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.977s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.998s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[3.020s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[3.043s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[3.064s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[3.086s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[3.107s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[3.116s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-16_15-00-58/robobin/command.log b/ros2/log/build_2024-12-16_15-00-58/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-00-58/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-00-58/robobin/stderr.log b/ros2/log/build_2024-12-16_15-00-58/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_15-00-58/robobin/stdout.log b/ros2/log/build_2024-12-16_15-00-58/robobin/stdout.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-00-58/robobin/stdout.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-00-58/robobin/stdout_stderr.log b/ros2/log/build_2024-12-16_15-00-58/robobin/stdout_stderr.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-00-58/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-00-58/robobin/streams.log b/ros2/log/build_2024-12-16_15-00-58/robobin/streams.log
deleted file mode 100644
index 04abd3cfeb411f5b5c76e1373773082b37adb800..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-00-58/robobin/streams.log
+++ /dev/null
@@ -1,26 +0,0 @@
-[1.471s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[1.880s] running egg_info
-[1.908s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[1.908s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[1.914s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[1.925s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[1.930s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[1.994s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.995s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.995s] running build
-[1.995s] running build_py
-[1.995s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.996s] running install
-[2.008s] running install_lib
-[2.044s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[2.045s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.050s] running install_data
-[2.050s] running install_egg_info
-[2.080s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.080s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.081s] running install_scripts
-[2.284s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.284s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.293s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.302s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.401s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-02-53/events.log b/ros2/log/build_2024-12-16_15-02-53/events.log
deleted file mode 100644
index b3a1024e8ff8a6c21759d799c0da2b8fa0451ed2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-02-53/events.log
+++ /dev/null
@@ -1,54 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000416] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000882] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099666] (-) TimerEvent: {}
-[0.200031] (-) TimerEvent: {}
-[0.300396] (-) TimerEvent: {}
-[0.401944] (-) TimerEvent: {}
-[0.503845] (-) TimerEvent: {}
-[0.604564] (-) TimerEvent: {}
-[0.705077] (-) TimerEvent: {}
-[0.805408] (-) TimerEvent: {}
-[0.905762] (-) TimerEvent: {}
-[1.006130] (-) TimerEvent: {}
-[1.106491] (-) TimerEvent: {}
-[1.206813] (-) TimerEvent: {}
-[1.307158] (-) TimerEvent: {}
-[1.407520] (-) TimerEvent: {}
-[1.461243] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'SYSTEMD_EXEC_PID': '1626', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/session.slice/org.gnome.Shell@wayland.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1593,unix/robobin-desktop:/tmp/.ICE-unix/1593', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/ea7f1a2b_3a39_4f21_8a31_dd3a276c0cc6', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.OOYBZ2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.110', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.507629] (-) TimerEvent: {}
-[1.607994] (-) TimerEvent: {}
-[1.708324] (-) TimerEvent: {}
-[1.808652] (-) TimerEvent: {}
-[1.865206] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.892637] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.893092] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.894485] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.895161] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.895859] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[1.908754] (-) TimerEvent: {}
-[1.961064] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.962223] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.962518] (robobin) StdoutLine: {'line': b'running build\n'}
-[1.962682] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[1.962906] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.963696] (robobin) StdoutLine: {'line': b'running install\n'}
-[1.973110] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.000251] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.001469] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.006317] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.006525] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.008812] (-) TimerEvent: {}
-[2.038507] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.039033] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.040310] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.108946] (-) TimerEvent: {}
-[2.210020] (-) TimerEvent: {}
-[2.239305] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.239674] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.241264] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.242969] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.310149] (-) TimerEvent: {}
-[2.333194] (robobin) CommandEnded: {'returncode': 0}
-[2.347224] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.348972] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-16_15-02-53/logger_all.log b/ros2/log/build_2024-12-16_15-02-53/logger_all.log
deleted file mode 100644
index 69ef23908761bd469a83c2c95ef20701c22a7663..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-02-53/logger_all.log
+++ /dev/null
@@ -1,137 +0,0 @@
-[0.154s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.154s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffffb12ad760>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffffb12ad460>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffffb12ad460>>, mixin_verb=('build',))
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.212s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.260s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.261s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.261s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.261s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.261s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.261s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.285s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.285s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.287s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/install
-[0.288s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.290s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.293s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.363s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.363s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.365s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.365s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.366s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.372s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.373s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.375s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.377s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.380s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.380s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.755s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.755s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.755s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.829s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.698s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.701s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.702s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.702s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.703s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.703s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.703s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.703s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.703s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.704s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.705s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.706s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.706s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.706s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.707s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.708s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.709s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.710s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.711s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.712s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.712s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.712s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.713s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.728s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.728s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.728s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.755s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.756s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.757s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.759s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.761s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[2.763s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[2.764s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[2.767s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[2.768s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[2.770s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[2.771s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-16_15-02-53/robobin/command.log b/ros2/log/build_2024-12-16_15-02-53/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-02-53/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-02-53/robobin/stderr.log b/ros2/log/build_2024-12-16_15-02-53/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_15-02-53/robobin/stdout.log b/ros2/log/build_2024-12-16_15-02-53/robobin/stdout.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-02-53/robobin/stdout.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-02-53/robobin/stdout_stderr.log b/ros2/log/build_2024-12-16_15-02-53/robobin/stdout_stderr.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-02-53/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-02-53/robobin/streams.log b/ros2/log/build_2024-12-16_15-02-53/robobin/streams.log
deleted file mode 100644
index 9520048909c9a5dc41a6cbd0e5970ceaf60be405..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-02-53/robobin/streams.log
+++ /dev/null
@@ -1,26 +0,0 @@
-[1.463s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[1.864s] running egg_info
-[1.891s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[1.892s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[1.893s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[1.894s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[1.895s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[1.960s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.961s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.961s] running build
-[1.961s] running build_py
-[1.962s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.962s] running install
-[1.972s] running install_lib
-[1.999s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[2.000s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.005s] running install_data
-[2.005s] running install_egg_info
-[2.037s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.038s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.039s] running install_scripts
-[2.238s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.238s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.240s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.242s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.332s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-06-25/events.log b/ros2/log/build_2024-12-16_15-06-25/events.log
deleted file mode 100644
index d5925a8a939c511fb6ca0ef9739907b02ae61869..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-06-25/events.log
+++ /dev/null
@@ -1,55 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000420] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000776] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099705] (-) TimerEvent: {}
-[0.200128] (-) TimerEvent: {}
-[0.300525] (-) TimerEvent: {}
-[0.400907] (-) TimerEvent: {}
-[0.501415] (-) TimerEvent: {}
-[0.602490] (-) TimerEvent: {}
-[0.703058] (-) TimerEvent: {}
-[0.803558] (-) TimerEvent: {}
-[0.903891] (-) TimerEvent: {}
-[1.004295] (-) TimerEvent: {}
-[1.104629] (-) TimerEvent: {}
-[1.204970] (-) TimerEvent: {}
-[1.305289] (-) TimerEvent: {}
-[1.405634] (-) TimerEvent: {}
-[1.506052] (-) TimerEvent: {}
-[1.529521] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'SYSTEMD_EXEC_PID': '1626', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/session.slice/org.gnome.Shell@wayland.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1593,unix/robobin-desktop:/tmp/.ICE-unix/1593', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/ea7f1a2b_3a39_4f21_8a31_dd3a276c0cc6', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.OOYBZ2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.110', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.606171] (-) TimerEvent: {}
-[1.706519] (-) TimerEvent: {}
-[1.806849] (-) TimerEvent: {}
-[1.907205] (-) TimerEvent: {}
-[1.947123] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.974106] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.974541] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.992185] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.993056] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.993726] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.007272] (-) TimerEvent: {}
-[2.058509] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.059697] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.059980] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.060120] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.060389] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[2.061184] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.070835] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.098044] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.099272] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.104108] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.104318] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.107338] (-) TimerEvent: {}
-[2.140293] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.140785] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.143968] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.207453] (-) TimerEvent: {}
-[2.307786] (-) TimerEvent: {}
-[2.350737] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.351093] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.354096] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.355723] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.407914] (-) TimerEvent: {}
-[2.454813] (robobin) CommandEnded: {'returncode': 0}
-[2.469228] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.470366] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-16_15-06-25/logger_all.log b/ros2/log/build_2024-12-16_15-06-25/logger_all.log
deleted file mode 100644
index 44e7dcfef8c82c9ddd1d74591af0689bb1040234..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-06-25/logger_all.log
+++ /dev/null
@@ -1,137 +0,0 @@
-[0.153s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.153s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff9176d730>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff9176d3d0>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff9176d3d0>>, mixin_verb=('build',))
-[0.210s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.210s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.210s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.210s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.210s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.211s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.211s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.258s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.258s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.258s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.258s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.258s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.258s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.283s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.283s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.285s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/install
-[0.286s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.288s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.291s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.360s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.360s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.362s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.362s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.362s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.370s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.371s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.374s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.378s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.379s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.380s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.790s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.791s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.791s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.895s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.817s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.820s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.820s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.821s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.821s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.821s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.822s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.822s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.822s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.823s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.824s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.825s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.825s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.825s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.826s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.827s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.828s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.829s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.830s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.831s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.831s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.831s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.831s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.851s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.851s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.851s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.883s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.884s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.887s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.890s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.892s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[2.893s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[2.895s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[2.898s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[2.899s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[2.901s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[2.903s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-16_15-06-25/robobin/command.log b/ros2/log/build_2024-12-16_15-06-25/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-06-25/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-06-25/robobin/stderr.log b/ros2/log/build_2024-12-16_15-06-25/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_15-06-25/robobin/stdout.log b/ros2/log/build_2024-12-16_15-06-25/robobin/stdout.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-06-25/robobin/stdout.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-06-25/robobin/stdout_stderr.log b/ros2/log/build_2024-12-16_15-06-25/robobin/stdout_stderr.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-06-25/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-06-25/robobin/streams.log b/ros2/log/build_2024-12-16_15-06-25/robobin/streams.log
deleted file mode 100644
index d315ea3b49b25b77309693ddafaa321f73af1920..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-06-25/robobin/streams.log
+++ /dev/null
@@ -1,26 +0,0 @@
-[1.532s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[1.946s] running egg_info
-[1.973s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[1.974s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[1.991s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[1.992s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[1.993s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[2.058s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.059s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.059s] running build
-[2.059s] running build_py
-[2.059s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[2.060s] running install
-[2.070s] running install_lib
-[2.097s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[2.098s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.103s] running install_data
-[2.103s] running install_egg_info
-[2.139s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.140s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.143s] running install_scripts
-[2.350s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.350s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.353s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.355s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.454s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-07-15/events.log b/ros2/log/build_2024-12-16_15-07-15/events.log
deleted file mode 100644
index 99a14e514955ff07212a34683bff18defd03905a..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-07-15/events.log
+++ /dev/null
@@ -1,55 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000309] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000862] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099707] (-) TimerEvent: {}
-[0.200082] (-) TimerEvent: {}
-[0.300449] (-) TimerEvent: {}
-[0.400866] (-) TimerEvent: {}
-[0.505013] (-) TimerEvent: {}
-[0.605599] (-) TimerEvent: {}
-[0.706196] (-) TimerEvent: {}
-[0.806748] (-) TimerEvent: {}
-[0.907069] (-) TimerEvent: {}
-[1.007418] (-) TimerEvent: {}
-[1.107743] (-) TimerEvent: {}
-[1.208071] (-) TimerEvent: {}
-[1.308412] (-) TimerEvent: {}
-[1.408770] (-) TimerEvent: {}
-[1.509269] (-) TimerEvent: {}
-[1.541034] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'SYSTEMD_EXEC_PID': '1626', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/session.slice/org.gnome.Shell@wayland.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1593,unix/robobin-desktop:/tmp/.ICE-unix/1593', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/ea7f1a2b_3a39_4f21_8a31_dd3a276c0cc6', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.OOYBZ2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.110', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.609332] (-) TimerEvent: {}
-[1.709704] (-) TimerEvent: {}
-[1.810072] (-) TimerEvent: {}
-[1.910421] (-) TimerEvent: {}
-[1.962214] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.988875] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.989303] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.990652] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.991234] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.992137] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.010511] (-) TimerEvent: {}
-[2.055710] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.056894] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.057172] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.057358] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.057573] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[2.058778] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.068060] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.096654] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.097904] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.102817] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.103054] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.110583] (-) TimerEvent: {}
-[2.138505] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.139113] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.140505] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.210697] (-) TimerEvent: {}
-[2.311058] (-) TimerEvent: {}
-[2.356513] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.356852] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.358288] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.359856] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.411190] (-) TimerEvent: {}
-[2.457121] (robobin) CommandEnded: {'returncode': 0}
-[2.472098] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.473571] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-16_15-07-15/logger_all.log b/ros2/log/build_2024-12-16_15-07-15/logger_all.log
deleted file mode 100644
index 40ca33f2a08003d8a6ff3cf6566bb0a236663450..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-07-15/logger_all.log
+++ /dev/null
@@ -1,137 +0,0 @@
-[0.155s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.155s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffffa4b6d7c0>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffffa4b6d430>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffffa4b6d430>>, mixin_verb=('build',))
-[0.213s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.213s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.214s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.214s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.214s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.214s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.214s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.215s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.263s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.263s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.263s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.263s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.263s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.263s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.288s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.288s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.291s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/install
-[0.291s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.294s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.296s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.365s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.365s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.365s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.365s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.365s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.365s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.365s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.365s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.365s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.365s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.366s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.367s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.367s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.368s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.375s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.376s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.377s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.380s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.381s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.381s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.814s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.815s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.815s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.911s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.824s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.827s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.828s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.829s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.829s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.830s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.830s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.830s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.830s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.831s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.832s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.833s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.833s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.833s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.834s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.835s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.836s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.837s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.838s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.839s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.839s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.839s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.840s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.861s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.861s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.861s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.892s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.892s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.893s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.895s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.898s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[2.899s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[2.901s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[2.903s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[2.904s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[2.907s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[2.909s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-16_15-07-15/robobin/command.log b/ros2/log/build_2024-12-16_15-07-15/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-07-15/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-07-15/robobin/stderr.log b/ros2/log/build_2024-12-16_15-07-15/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_15-07-15/robobin/stdout.log b/ros2/log/build_2024-12-16_15-07-15/robobin/stdout.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-07-15/robobin/stdout.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-07-15/robobin/stdout_stderr.log b/ros2/log/build_2024-12-16_15-07-15/robobin/stdout_stderr.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-07-15/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-07-15/robobin/streams.log b/ros2/log/build_2024-12-16_15-07-15/robobin/streams.log
deleted file mode 100644
index a37ddae3724b15402a8d0abcbb72b063212db691..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-07-15/robobin/streams.log
+++ /dev/null
@@ -1,26 +0,0 @@
-[1.543s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[1.961s] running egg_info
-[1.988s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[1.988s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[1.990s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[1.990s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[1.991s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[2.055s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.056s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.056s] running build
-[2.056s] running build_py
-[2.056s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[2.058s] running install
-[2.067s] running install_lib
-[2.096s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[2.097s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.102s] running install_data
-[2.102s] running install_egg_info
-[2.138s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.138s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.139s] running install_scripts
-[2.356s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.356s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.357s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.359s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.456s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-08-31/events.log b/ros2/log/build_2024-12-16_15-08-31/events.log
deleted file mode 100644
index 3f640d60f179d5c5822f06b69a1625e4258a3340..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-08-31/events.log
+++ /dev/null
@@ -1,56 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000418] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000782] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099702] (-) TimerEvent: {}
-[0.200087] (-) TimerEvent: {}
-[0.300469] (-) TimerEvent: {}
-[0.402478] (-) TimerEvent: {}
-[0.502944] (-) TimerEvent: {}
-[0.605083] (-) TimerEvent: {}
-[0.705563] (-) TimerEvent: {}
-[0.805947] (-) TimerEvent: {}
-[0.909420] (-) TimerEvent: {}
-[1.009757] (-) TimerEvent: {}
-[1.110082] (-) TimerEvent: {}
-[1.210425] (-) TimerEvent: {}
-[1.310745] (-) TimerEvent: {}
-[1.411090] (-) TimerEvent: {}
-[1.509083] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'SYSTEMD_EXEC_PID': '1626', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/session.slice/org.gnome.Shell@wayland.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1593,unix/robobin-desktop:/tmp/.ICE-unix/1593', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/ea7f1a2b_3a39_4f21_8a31_dd3a276c0cc6', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.OOYBZ2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.110', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.512518] (-) TimerEvent: {}
-[1.614228] (-) TimerEvent: {}
-[1.714811] (-) TimerEvent: {}
-[1.815184] (-) TimerEvent: {}
-[1.915516] (-) TimerEvent: {}
-[2.015838] (-) TimerEvent: {}
-[2.017343] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[2.051831] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[2.052278] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[2.053280] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[2.053933] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[2.054698] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.110521] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.111673] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.111931] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.112066] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.112335] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[2.113061] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.115899] (-) TimerEvent: {}
-[2.124174] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.154692] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.155906] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.160708] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.160939] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.192583] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.193138] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.196172] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.215976] (-) TimerEvent: {}
-[2.316240] (-) TimerEvent: {}
-[2.401415] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.401731] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.403122] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.404795] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.416344] (-) TimerEvent: {}
-[2.502776] (robobin) CommandEnded: {'returncode': 0}
-[2.516424] (-) TimerEvent: {}
-[2.524797] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.526581] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-16_15-08-31/logger_all.log b/ros2/log/build_2024-12-16_15-08-31/logger_all.log
deleted file mode 100644
index 67b6a7db20ef2fc6a2efa1c50daccd8f45132c43..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-08-31/logger_all.log
+++ /dev/null
@@ -1,137 +0,0 @@
-[0.156s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.156s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff84d9d760>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff84d9d3d0>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff84d9d3d0>>, mixin_verb=('build',))
-[0.213s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.214s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.214s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.214s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.214s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.214s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.214s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.214s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.257s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.258s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.259s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.262s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.262s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.262s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.262s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.262s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.262s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.287s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.287s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.289s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/install
-[0.290s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.292s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.295s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.363s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.364s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.364s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.365s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.366s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.366s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.373s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.374s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.376s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.378s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.380s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.380s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.795s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.795s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.795s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.877s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.868s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.871s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.871s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.872s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.872s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.873s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.873s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.873s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.873s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.874s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.876s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.877s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.877s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.878s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.879s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.880s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.881s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.884s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.887s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.889s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.891s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.891s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.891s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.910s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.910s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.910s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.935s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.935s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.937s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.938s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.941s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[2.942s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[2.943s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[2.945s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[2.946s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[2.948s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[2.949s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-16_15-08-31/robobin/command.log b/ros2/log/build_2024-12-16_15-08-31/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-08-31/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-08-31/robobin/stderr.log b/ros2/log/build_2024-12-16_15-08-31/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_15-08-31/robobin/stdout.log b/ros2/log/build_2024-12-16_15-08-31/robobin/stdout.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-08-31/robobin/stdout.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-08-31/robobin/stdout_stderr.log b/ros2/log/build_2024-12-16_15-08-31/robobin/stdout_stderr.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-08-31/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-08-31/robobin/streams.log b/ros2/log/build_2024-12-16_15-08-31/robobin/streams.log
deleted file mode 100644
index 18b325258c901420b87a2480086669329333b820..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-08-31/robobin/streams.log
+++ /dev/null
@@ -1,26 +0,0 @@
-[1.511s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.017s] running egg_info
-[2.051s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[2.051s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[2.052s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[2.053s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[2.054s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[2.110s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.111s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.111s] running build
-[2.111s] running build_py
-[2.111s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[2.112s] running install
-[2.123s] running install_lib
-[2.154s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[2.155s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.160s] running install_data
-[2.160s] running install_egg_info
-[2.192s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.192s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.195s] running install_scripts
-[2.401s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.401s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.402s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.404s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.502s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-12-12/events.log b/ros2/log/build_2024-12-16_15-12-12/events.log
deleted file mode 100644
index 24a7819757aa2e25a894853f9b60b2c62a0a0a36..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-12-12/events.log
+++ /dev/null
@@ -1,55 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000410] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000949] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099693] (-) TimerEvent: {}
-[0.200123] (-) TimerEvent: {}
-[0.300490] (-) TimerEvent: {}
-[0.400881] (-) TimerEvent: {}
-[0.504203] (-) TimerEvent: {}
-[0.604704] (-) TimerEvent: {}
-[0.706653] (-) TimerEvent: {}
-[0.807165] (-) TimerEvent: {}
-[0.907517] (-) TimerEvent: {}
-[1.007844] (-) TimerEvent: {}
-[1.108168] (-) TimerEvent: {}
-[1.208508] (-) TimerEvent: {}
-[1.308819] (-) TimerEvent: {}
-[1.409163] (-) TimerEvent: {}
-[1.509577] (-) TimerEvent: {}
-[1.521701] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'SYSTEMD_EXEC_PID': '1626', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/session.slice/org.gnome.Shell@wayland.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1593,unix/robobin-desktop:/tmp/.ICE-unix/1593', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/ea7f1a2b_3a39_4f21_8a31_dd3a276c0cc6', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.OOYBZ2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.110', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.609699] (-) TimerEvent: {}
-[1.710061] (-) TimerEvent: {}
-[1.810394] (-) TimerEvent: {}
-[1.910715] (-) TimerEvent: {}
-[1.946403] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.973856] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.974346] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.975322] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.975953] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.976565] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.010815] (-) TimerEvent: {}
-[2.039376] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.040562] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.040812] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.040969] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.041211] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[2.042006] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.051560] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.078614] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.079869] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.084684] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.084888] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.110883] (-) TimerEvent: {}
-[2.119381] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.120118] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.124551] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.211008] (-) TimerEvent: {}
-[2.311366] (-) TimerEvent: {}
-[2.359506] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.359880] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.361394] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.363080] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.411496] (-) TimerEvent: {}
-[2.464519] (robobin) CommandEnded: {'returncode': 0}
-[2.481350] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.482856] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-16_15-12-12/logger_all.log b/ros2/log/build_2024-12-16_15-12-12/logger_all.log
deleted file mode 100644
index e115dd05823f41a4b131d72873d88304e680587b..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-12-12/logger_all.log
+++ /dev/null
@@ -1,137 +0,0 @@
-[0.153s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.154s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff83331730>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff83331430>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff83331430>>, mixin_verb=('build',))
-[0.211s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.211s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.211s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.211s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.211s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.211s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.211s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.259s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.284s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.284s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.286s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/install
-[0.286s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.289s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.292s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.360s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.360s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.361s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.362s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.362s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.369s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.370s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.372s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.374s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.376s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.376s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.780s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.781s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.781s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.886s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.826s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.829s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.829s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.830s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.830s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.831s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.831s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.831s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.831s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.832s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.833s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.834s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.834s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.835s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.836s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.837s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.838s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.839s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.841s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.842s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.843s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.843s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.843s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.861s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.861s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.862s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.896s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.897s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.902s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.905s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.907s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[2.908s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[2.910s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[2.913s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[2.915s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[2.917s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[2.919s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-16_15-12-12/robobin/command.log b/ros2/log/build_2024-12-16_15-12-12/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-12-12/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-12-12/robobin/stderr.log b/ros2/log/build_2024-12-16_15-12-12/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_15-12-12/robobin/stdout.log b/ros2/log/build_2024-12-16_15-12-12/robobin/stdout.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-12-12/robobin/stdout.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-12-12/robobin/stdout_stderr.log b/ros2/log/build_2024-12-16_15-12-12/robobin/stdout_stderr.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-12-12/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-12-12/robobin/streams.log b/ros2/log/build_2024-12-16_15-12-12/robobin/streams.log
deleted file mode 100644
index 0e95851ea96f78ce5e698c772140596e63c9b309..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-12-12/robobin/streams.log
+++ /dev/null
@@ -1,26 +0,0 @@
-[1.524s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[1.946s] running egg_info
-[1.973s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[1.973s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[1.974s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[1.975s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[1.976s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[2.039s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.040s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.040s] running build
-[2.040s] running build_py
-[2.040s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[2.041s] running install
-[2.051s] running install_lib
-[2.078s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[2.079s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.084s] running install_data
-[2.084s] running install_egg_info
-[2.119s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.119s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.124s] running install_scripts
-[2.359s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.359s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.361s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.362s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.464s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-19-26/events.log b/ros2/log/build_2024-12-16_15-19-26/events.log
deleted file mode 100644
index 430ebc7ca47c7a9f842237eb777b195fc16f098c..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-19-26/events.log
+++ /dev/null
@@ -1,55 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000328] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.001015] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099672] (-) TimerEvent: {}
-[0.200056] (-) TimerEvent: {}
-[0.300428] (-) TimerEvent: {}
-[0.400813] (-) TimerEvent: {}
-[0.501298] (-) TimerEvent: {}
-[0.601880] (-) TimerEvent: {}
-[0.702724] (-) TimerEvent: {}
-[0.803207] (-) TimerEvent: {}
-[0.903555] (-) TimerEvent: {}
-[1.003891] (-) TimerEvent: {}
-[1.104236] (-) TimerEvent: {}
-[1.204893] (-) TimerEvent: {}
-[1.305225] (-) TimerEvent: {}
-[1.405629] (-) TimerEvent: {}
-[1.506111] (-) TimerEvent: {}
-[1.515504] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'SYSTEMD_EXEC_PID': '1626', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/session.slice/org.gnome.Shell@wayland.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1593,unix/robobin-desktop:/tmp/.ICE-unix/1593', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/ea7f1a2b_3a39_4f21_8a31_dd3a276c0cc6', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.OOYBZ2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.110', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.606222] (-) TimerEvent: {}
-[1.706581] (-) TimerEvent: {}
-[1.806909] (-) TimerEvent: {}
-[1.907246] (-) TimerEvent: {}
-[1.943473] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.970732] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.971165] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.972559] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.973399] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.974085] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.007338] (-) TimerEvent: {}
-[2.034949] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.036083] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.036382] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.036546] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.036766] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[2.037497] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.046868] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.073868] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.075089] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.079984] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.080205] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.107436] (-) TimerEvent: {}
-[2.111010] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.114773] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.116727] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.207558] (-) TimerEvent: {}
-[2.307953] (-) TimerEvent: {}
-[2.350499] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.351329] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.352191] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.353997] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.408073] (-) TimerEvent: {}
-[2.458713] (robobin) CommandEnded: {'returncode': 0}
-[2.473819] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.475161] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-16_15-19-26/logger_all.log b/ros2/log/build_2024-12-16_15-19-26/logger_all.log
deleted file mode 100644
index a696a3e041f1520ac88abac50d9c9e83e3fe9fe4..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-19-26/logger_all.log
+++ /dev/null
@@ -1,137 +0,0 @@
-[0.153s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.154s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffffb579d6d0>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffffb579d340>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffffb579d340>>, mixin_verb=('build',))
-[0.210s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.211s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.211s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.211s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.211s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.211s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.211s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.256s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.259s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.284s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.284s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.286s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/install
-[0.287s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.289s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.292s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.360s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.360s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.360s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.362s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.362s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.363s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.371s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.371s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.374s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.375s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.378s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.378s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.786s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.787s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.787s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.885s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.821s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.823s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.824s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.825s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.825s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.825s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.826s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.826s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.826s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.827s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.828s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.830s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.830s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.830s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.831s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.832s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.833s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.834s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.835s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.835s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.836s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.836s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.836s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.855s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.855s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.855s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.890s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.891s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.896s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.899s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.901s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[2.902s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[2.903s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[2.906s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[2.907s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[2.909s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[2.910s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-16_15-19-26/robobin/command.log b/ros2/log/build_2024-12-16_15-19-26/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-19-26/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-19-26/robobin/stderr.log b/ros2/log/build_2024-12-16_15-19-26/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_15-19-26/robobin/stdout.log b/ros2/log/build_2024-12-16_15-19-26/robobin/stdout.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-19-26/robobin/stdout.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-19-26/robobin/stdout_stderr.log b/ros2/log/build_2024-12-16_15-19-26/robobin/stdout_stderr.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-19-26/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-19-26/robobin/streams.log b/ros2/log/build_2024-12-16_15-19-26/robobin/streams.log
deleted file mode 100644
index 7e66a2ca0aa7d073be46cdd6fd62869a04ed885e..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-19-26/robobin/streams.log
+++ /dev/null
@@ -1,26 +0,0 @@
-[1.520s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[1.943s] running egg_info
-[1.970s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[1.970s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[1.972s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[1.972s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[1.973s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[2.034s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.035s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.035s] running build
-[2.036s] running build_py
-[2.036s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[2.037s] running install
-[2.046s] running install_lib
-[2.073s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[2.074s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.079s] running install_data
-[2.079s] running install_egg_info
-[2.111s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.114s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.116s] running install_scripts
-[2.350s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.350s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.351s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.353s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.458s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-21-29/events.log b/ros2/log/build_2024-12-16_15-21-29/events.log
deleted file mode 100644
index 59e0fa3a87bd4075d0ebd23e027fcd500c08bb42..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-21-29/events.log
+++ /dev/null
@@ -1,55 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000446] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000833] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099694] (-) TimerEvent: {}
-[0.200138] (-) TimerEvent: {}
-[0.300496] (-) TimerEvent: {}
-[0.400866] (-) TimerEvent: {}
-[0.501413] (-) TimerEvent: {}
-[0.601876] (-) TimerEvent: {}
-[0.702249] (-) TimerEvent: {}
-[0.805727] (-) TimerEvent: {}
-[0.906062] (-) TimerEvent: {}
-[1.006400] (-) TimerEvent: {}
-[1.106735] (-) TimerEvent: {}
-[1.207074] (-) TimerEvent: {}
-[1.307398] (-) TimerEvent: {}
-[1.407752] (-) TimerEvent: {}
-[1.507086] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'SYSTEMD_EXEC_PID': '1626', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/session.slice/org.gnome.Shell@wayland.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1593,unix/robobin-desktop:/tmp/.ICE-unix/1593', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/ea7f1a2b_3a39_4f21_8a31_dd3a276c0cc6', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.OOYBZ2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.110', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.510665] (-) TimerEvent: {}
-[1.611462] (-) TimerEvent: {}
-[1.711802] (-) TimerEvent: {}
-[1.812127] (-) TimerEvent: {}
-[1.912462] (-) TimerEvent: {}
-[1.945022] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.972834] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.973292] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.974712] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.975976] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.977386] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.012541] (-) TimerEvent: {}
-[2.041006] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.042133] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.042399] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.042539] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.042800] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[2.043531] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.052927] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.079960] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.081188] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.086049] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.086289] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.112629] (-) TimerEvent: {}
-[2.121103] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.122585] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.125929] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.212748] (-) TimerEvent: {}
-[2.313113] (-) TimerEvent: {}
-[2.358736] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.359077] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.360662] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.362306] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.413259] (-) TimerEvent: {}
-[2.469843] (robobin) CommandEnded: {'returncode': 0}
-[2.487144] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.491100] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-16_15-21-29/logger_all.log b/ros2/log/build_2024-12-16_15-21-29/logger_all.log
deleted file mode 100644
index b31ec5d86c114eb158be52d002c3fb108dd50179..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-21-29/logger_all.log
+++ /dev/null
@@ -1,137 +0,0 @@
-[0.158s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.158s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff85a6d6a0>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff85a6d3d0>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff85a6d3d0>>, mixin_verb=('build',))
-[0.217s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.218s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.218s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.218s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.218s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.218s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.218s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.218s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.219s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.261s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.262s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.265s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.265s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.265s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.265s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.265s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.265s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.268s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.268s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.268s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.268s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.268s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.268s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.293s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.294s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.296s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/install
-[0.297s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.299s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.302s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.371s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.371s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.371s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.371s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.371s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.371s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.371s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.371s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.371s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.371s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.371s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.373s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.373s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.374s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.382s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.382s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.386s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.388s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.394s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.395s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.802s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.802s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.803s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.883s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.843s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.845s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.846s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.847s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.847s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.847s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.848s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.848s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.848s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.849s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.850s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.851s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.851s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.851s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.852s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.853s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.855s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.857s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.858s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.859s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.860s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.860s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.860s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.887s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.888s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.888s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.921s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.922s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.923s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.925s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.927s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[2.928s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[2.929s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[2.932s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[2.933s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[2.935s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[2.936s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-16_15-21-29/robobin/command.log b/ros2/log/build_2024-12-16_15-21-29/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-21-29/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_15-21-29/robobin/stderr.log b/ros2/log/build_2024-12-16_15-21-29/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_15-21-29/robobin/stdout.log b/ros2/log/build_2024-12-16_15-21-29/robobin/stdout.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-21-29/robobin/stdout.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-21-29/robobin/stdout_stderr.log b/ros2/log/build_2024-12-16_15-21-29/robobin/stdout_stderr.log
deleted file mode 100644
index 93e9e05ac874c49027df4586d6ee3207fe7500b2..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-21-29/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_15-21-29/robobin/streams.log b/ros2/log/build_2024-12-16_15-21-29/robobin/streams.log
deleted file mode 100644
index 89501de7510249ba0d8f4ae626c8c04b8c6835cd..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_15-21-29/robobin/streams.log
+++ /dev/null
@@ -1,26 +0,0 @@
-[1.508s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[1.943s] running egg_info
-[1.971s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[1.971s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[1.973s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[1.974s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[1.975s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[2.039s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.040s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.040s] running build
-[2.040s] running build_py
-[2.041s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[2.041s] running install
-[2.051s] running install_lib
-[2.078s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[2.079s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.084s] running install_data
-[2.084s] running install_egg_info
-[2.119s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.121s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.124s] running install_scripts
-[2.357s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.357s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.359s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.360s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.468s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_16-30-47/events.log b/ros2/log/build_2024-12-16_16-30-47/events.log
deleted file mode 100644
index abc57fa3ce66579c9e891aea7f4f521b6becb12d..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_16-30-47/events.log
+++ /dev/null
@@ -1,60 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000435] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000882] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099695] (-) TimerEvent: {}
-[0.200055] (-) TimerEvent: {}
-[0.300424] (-) TimerEvent: {}
-[0.400783] (-) TimerEvent: {}
-[0.501825] (-) TimerEvent: {}
-[0.604424] (-) TimerEvent: {}
-[0.705035] (-) TimerEvent: {}
-[0.806451] (-) TimerEvent: {}
-[0.907307] (-) TimerEvent: {}
-[1.007651] (-) TimerEvent: {}
-[1.108010] (-) TimerEvent: {}
-[1.208351] (-) TimerEvent: {}
-[1.308677] (-) TimerEvent: {}
-[1.409016] (-) TimerEvent: {}
-[1.509344] (-) TimerEvent: {}
-[1.609697] (-) TimerEvent: {}
-[1.710166] (-) TimerEvent: {}
-[1.764490] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin/ros2/src', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'DBUS_STARTER_BUS_TYPE': 'session', 'SYSTEMD_EXEC_PID': '1594', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/src/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/app.slice/app-gnome\\x2dsession\\x2dmanager.slice/gnome-session-manager@ubuntu.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1594,unix/robobin-desktop:/tmp/.ICE-unix/1594', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/92f2849b_1746_4562_850c_1b14829cbe47', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.XGQ7Y2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.102', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/src/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'DBUS_STARTER_ADDRESS': 'unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.810283] (-) TimerEvent: {}
-[1.910647] (-) TimerEvent: {}
-[2.010998] (-) TimerEvent: {}
-[2.111332] (-) TimerEvent: {}
-[2.211662] (-) TimerEvent: {}
-[2.244400] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[2.272771] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[2.273228] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[2.274225] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[2.274844] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[2.275518] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.311763] (-) TimerEvent: {}
-[2.343806] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.345447] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.345952] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.346098] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.346565] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[2.347349] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.356947] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.385052] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.390329] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.396283] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.396576] (robobin) StdoutLine: {'line': b'copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch\n'}
-[2.396838] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.411836] (-) TimerEvent: {}
-[2.438826] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.440336] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.441317] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.511946] (-) TimerEvent: {}
-[2.612291] (-) TimerEvent: {}
-[2.706789] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.707137] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.708266] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.709404] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.712380] (-) TimerEvent: {}
-[2.812833] (-) TimerEvent: {}
-[2.831441] (robobin) CommandEnded: {'returncode': 0}
-[2.855276] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.857835] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-16_16-30-47/logger_all.log b/ros2/log/build_2024-12-16_16-30-47/logger_all.log
deleted file mode 100644
index 246455aabde2cc9ffc6cf22924c59c354431128c..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_16-30-47/logger_all.log
+++ /dev/null
@@ -1,137 +0,0 @@
-[0.171s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.171s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffffb359d370>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffffb359d040>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffffb359d040>>, mixin_verb=('build',))
-[0.230s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.230s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.230s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.231s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.231s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.231s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.231s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.232s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.233s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.290s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.291s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.291s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.291s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.291s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.291s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.291s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.291s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.291s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.291s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.291s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.291s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.292s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.293s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.294s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.297s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.297s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.297s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.297s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.297s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.298s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.322s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.322s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.325s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/src/install
-[0.325s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.328s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.335s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.408s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.408s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.408s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.408s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.408s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.408s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.408s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.408s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.408s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.408s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.409s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.410s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.410s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.411s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.417s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.418s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.420s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.423s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.427s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.427s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.902s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.903s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.903s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[2.178s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[3.242s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[3.246s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[3.247s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[3.248s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[3.249s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[3.249s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[3.249s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[3.250s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[3.250s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[3.252s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[3.254s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[3.255s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[3.255s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[3.256s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[3.257s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[3.258s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[3.260s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[3.262s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[3.263s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[3.265s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[3.265s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[3.265s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[3.266s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[3.278s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[3.278s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[3.278s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[3.310s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[3.312s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[3.314s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[3.316s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[3.319s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[3.320s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[3.323s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[3.326s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[3.327s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[3.329s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[3.330s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-16_16-30-47/robobin/command.log b/ros2/log/build_2024-12-16_16-30-47/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_16-30-47/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-16_16-30-47/robobin/stderr.log b/ros2/log/build_2024-12-16_16-30-47/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-16_16-30-47/robobin/stdout.log b/ros2/log/build_2024-12-16_16-30-47/robobin/stdout.log
deleted file mode 100644
index bcb58358708e2434cbac28c068468985da9104e7..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_16-30-47/robobin/stdout.log
+++ /dev/null
@@ -1,25 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_16-30-47/robobin/stdout_stderr.log b/ros2/log/build_2024-12-16_16-30-47/robobin/stdout_stderr.log
deleted file mode 100644
index bcb58358708e2434cbac28c068468985da9104e7..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_16-30-47/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,25 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-16_16-30-47/robobin/streams.log b/ros2/log/build_2024-12-16_16-30-47/robobin/streams.log
deleted file mode 100644
index c2076768cca127e01f8ae04bc21ecb6b180bfa1f..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-16_16-30-47/robobin/streams.log
+++ /dev/null
@@ -1,27 +0,0 @@
-[1.767s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.243s] running egg_info
-[2.271s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[2.272s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[2.273s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[2.273s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[2.274s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[2.343s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.344s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.345s] running build
-[2.345s] running build_py
-[2.345s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[2.346s] running install
-[2.356s] running install_lib
-[2.387s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[2.389s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.395s] running install_data
-[2.395s] copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-[2.395s] running install_egg_info
-[2.438s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.439s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.440s] running install_scripts
-[2.705s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.706s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.707s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.708s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.831s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-18_14-34-08/events.log b/ros2/log/build_2024-12-18_14-34-08/events.log
deleted file mode 100644
index c76b497b07e72bcc89813c3b17570d4c5ce31132..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_14-34-08/events.log
+++ /dev/null
@@ -1,107 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000378] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000681] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099620] (-) TimerEvent: {}
-[0.199903] (-) TimerEvent: {}
-[0.300156] (-) TimerEvent: {}
-[0.400441] (-) TimerEvent: {}
-[0.500731] (-) TimerEvent: {}
-[0.600987] (-) TimerEvent: {}
-[0.701259] (-) TimerEvent: {}
-[0.801514] (-) TimerEvent: {}
-[0.901766] (-) TimerEvent: {}
-[1.001972] (-) TimerEvent: {}
-[1.102203] (-) TimerEvent: {}
-[1.202968] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'SSH_CLIENT': '192.168.43.138 43375 22', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'tty', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin/ros2/src', 'SSH_TTY': '/dev/pts/0', 'ROS_PYTHON_VERSION': '3', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'XDG_SESSION_CLASS': 'user', 'TERM': 'xterm-256color', 'XDG_SESSION_ID': '4', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin', 'XDG_RUNTIME_DIR': '/run/user/1002', 'LANG': 'en_US.UTF-8', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'SSH_CONNECTION': '192.168.43.138 43375 192.168.43.18 22', 'XDG_DATA_DIRS': '/usr/share/gnome:/usr/local/share:/usr/share:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.206107] (-) TimerEvent: {}
-[1.306332] (-) TimerEvent: {}
-[1.406601] (-) TimerEvent: {}
-[1.506862] (-) TimerEvent: {}
-[1.579906] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.580407] (robobin) StdoutLine: {'line': b'creating ../../build/robobin/robobin.egg-info\n'}
-[1.606461] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.606852] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.606955] (-) TimerEvent: {}
-[1.607186] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.607332] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.607436] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[1.607585] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.661055] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.662023] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.662223] (robobin) StdoutLine: {'line': b'running build\n'}
-[1.662324] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[1.662534] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/build/robobin/build\n'}
-[1.662646] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/build/robobin/build/lib\n'}
-[1.662755] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.662860] (robobin) StdoutLine: {'line': b'copying robobin/encoder.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.663828] (robobin) StdoutLine: {'line': b'copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.664484] (robobin) StdoutLine: {'line': b'copying robobin/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.664627] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.664829] (robobin) StdoutLine: {'line': b'copying robobin/imu_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.665314] (robobin) StdoutLine: {'line': b'copying robobin/api_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.665831] (robobin) StdoutLine: {'line': b'copying robobin/control_feedback.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.665994] (robobin) StdoutLine: {'line': b'copying robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.666271] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers\n'}
-[1.666383] (robobin) StdoutLine: {'line': b'copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers\n'}
-[1.667271] (robobin) StdoutLine: {'line': b'copying robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers\n'}
-[1.667410] (robobin) StdoutLine: {'line': b'copying robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers\n'}
-[1.667577] (robobin) StdoutLine: {'line': b'copying robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers\n'}
-[1.667743] (robobin) StdoutLine: {'line': b'copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers\n'}
-[1.668499] (robobin) StdoutLine: {'line': b'running install\n'}
-[1.678010] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[1.705353] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.705537] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/encoder.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.705722] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.705889] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.706025] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.706253] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.706376] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.706541] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.706679] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.706858] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.707013] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.707101] (-) TimerEvent: {}
-[1.707296] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/imu_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.707467] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.707585] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/control_feedback.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.707694] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.708524] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/encoder.py to encoder.cpython-312.pyc\n'}
-[1.709495] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc\n'}
-[1.710669] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__init__.py to __init__.cpython-312.pyc\n'}
-[1.710928] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[1.718090] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc\n'}
-[1.720404] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py to __init__.cpython-312.pyc\n'}
-[1.720698] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py to realtime_location_cli_only.cpython-312.pyc\n'}
-[1.723858] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py to graph_maker.cpython-312.pyc\n'}
-[1.725232] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc\n'}
-[1.726432] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py to imu_node.cpython-312.pyc\n'}
-[1.727664] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc\n'}
-[1.729886] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py to control_feedback.cpython-312.pyc\n'}
-[1.731932] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py to uwb_pathing_node.cpython-312.pyc\n'}
-[1.733252] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[1.733399] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/install/robobin/share/ament_index\n'}
-[1.733500] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index\n'}
-[1.733600] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages\n'}
-[1.733716] (robobin) StdoutLine: {'line': b'copying resource/robobin -> /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages\n'}
-[1.733884] (robobin) StdoutLine: {'line': b'copying package.xml -> /home/robobin/robobin/ros2/install/robobin/share/robobin\n'}
-[1.734033] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/install/robobin/share/robobin/launch\n'}
-[1.734143] (robobin) StdoutLine: {'line': b'copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch\n'}
-[1.735044] (robobin) StdoutLine: {'line': b'copying launch/robobin_no_components_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch\n'}
-[1.735780] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[1.765019] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[1.774843] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[1.807187] (-) TimerEvent: {}
-[1.907421] (-) TimerEvent: {}
-[1.963342] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.963600] (robobin) StdoutLine: {'line': b'Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.963777] (robobin) StdoutLine: {'line': b'Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.963915] (robobin) StdoutLine: {'line': b'Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.964049] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.964173] (robobin) StdoutLine: {'line': b'Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.964294] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.964418] (robobin) StdoutLine: {'line': b'Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.965033] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.007516] (-) TimerEvent: {}
-[2.042000] (robobin) CommandEnded: {'returncode': 0}
-[2.054605] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.055474] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-18_14-34-08/logger_all.log b/ros2/log/build_2024-12-18_14-34-08/logger_all.log
deleted file mode 100644
index 27c516b363c10d2443649c42e9276f6891ccea92..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_14-34-08/logger_all.log
+++ /dev/null
@@ -1,138 +0,0 @@
-[0.152s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.152s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff862312b0>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff862310a0>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff862310a0>>, mixin_verb=('build',))
-[0.210s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.210s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.210s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.210s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.210s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.210s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.210s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.210s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.210s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.210s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.210s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.210s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.210s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.211s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.250s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.251s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.256s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.256s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.256s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.256s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.256s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.256s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.280s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.280s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.281s] WARNING:colcon.colcon_ros.prefix_path.ament:The path '/home/robobin/robobin/ros2/install/robobin' in the environment variable AMENT_PREFIX_PATH doesn't exist
-[0.283s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 0 installed packages in /home/robobin/robobin/ros2/install
-[0.283s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.285s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.288s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.355s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.355s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.355s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.355s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.355s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.356s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.356s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.356s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.356s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.356s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.356s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.357s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.358s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.358s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.360s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.360s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.361s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.362s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.363s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.363s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.690s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.691s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.691s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.563s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.399s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.402s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.403s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.404s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.404s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.404s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.404s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.405s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.405s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.405s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.406s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.407s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.407s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.407s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.408s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.409s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.409s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.410s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.411s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.412s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.412s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.412s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.412s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.419s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.419s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.419s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.435s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.435s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.436s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.438s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.439s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[2.440s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[2.440s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[2.442s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[2.442s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[2.444s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[2.444s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-18_14-34-08/robobin/command.log b/ros2/log/build_2024-12-18_14-34-08/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_14-34-08/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-18_14-34-08/robobin/stderr.log b/ros2/log/build_2024-12-18_14-34-08/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-18_14-34-08/robobin/stdout.log b/ros2/log/build_2024-12-18_14-34-08/robobin/stdout.log
deleted file mode 100644
index 019d2405bdf3496332906869420796aaf50ccd6f..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_14-34-08/robobin/stdout.log
+++ /dev/null
@@ -1,80 +0,0 @@
-running egg_info
-creating ../../build/robobin/robobin.egg-info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-creating /home/robobin/robobin/ros2/build/robobin/build
-creating /home/robobin/robobin/ros2/build/robobin/build/lib
-creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/encoder.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/imu_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/api_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/control_feedback.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-running install
-running install_lib
-creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/encoder.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/imu_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/control_feedback.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/encoder.py to encoder.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__init__.py to __init__.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py to __init__.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py to realtime_location_cli_only.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py to graph_maker.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py to imu_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py to control_feedback.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py to uwb_pathing_node.cpython-312.pyc
-running install_data
-creating /home/robobin/robobin/ros2/install/robobin/share/ament_index
-creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index
-creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages
-copying resource/robobin -> /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages
-copying package.xml -> /home/robobin/robobin/ros2/install/robobin/share/robobin
-creating /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-copying launch/robobin_no_components_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-running install_egg_info
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-18_14-34-08/robobin/stdout_stderr.log b/ros2/log/build_2024-12-18_14-34-08/robobin/stdout_stderr.log
deleted file mode 100644
index 019d2405bdf3496332906869420796aaf50ccd6f..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_14-34-08/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,80 +0,0 @@
-running egg_info
-creating ../../build/robobin/robobin.egg-info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-creating /home/robobin/robobin/ros2/build/robobin/build
-creating /home/robobin/robobin/ros2/build/robobin/build/lib
-creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/encoder.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/imu_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/api_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/control_feedback.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-running install
-running install_lib
-creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/encoder.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/imu_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/control_feedback.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/encoder.py to encoder.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__init__.py to __init__.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py to __init__.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py to realtime_location_cli_only.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py to graph_maker.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py to imu_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py to control_feedback.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py to uwb_pathing_node.cpython-312.pyc
-running install_data
-creating /home/robobin/robobin/ros2/install/robobin/share/ament_index
-creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index
-creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages
-copying resource/robobin -> /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages
-copying package.xml -> /home/robobin/robobin/ros2/install/robobin/share/robobin
-creating /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-copying launch/robobin_no_components_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-running install_egg_info
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-18_14-34-08/robobin/streams.log b/ros2/log/build_2024-12-18_14-34-08/robobin/streams.log
deleted file mode 100644
index b88d92941c596477633b43021e34f5ced5a86160..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_14-34-08/robobin/streams.log
+++ /dev/null
@@ -1,82 +0,0 @@
-[1.204s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[1.579s] running egg_info
-[1.580s] creating ../../build/robobin/robobin.egg-info
-[1.606s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[1.606s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[1.607s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[1.607s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[1.607s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[1.607s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.660s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.661s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.662s] running build
-[1.662s] running build_py
-[1.662s] creating /home/robobin/robobin/ros2/build/robobin/build
-[1.662s] creating /home/robobin/robobin/ros2/build/robobin/build/lib
-[1.662s] creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.662s] copying robobin/encoder.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.663s] copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.664s] copying robobin/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.664s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.664s] copying robobin/imu_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.665s] copying robobin/api_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.665s] copying robobin/control_feedback.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.665s] copying robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.666s] creating /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-[1.666s] copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-[1.667s] copying robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-[1.667s] copying robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-[1.667s] copying robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-[1.667s] copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-[1.668s] running install
-[1.677s] running install_lib
-[1.705s] creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.705s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/encoder.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.705s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.705s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.705s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.706s] creating /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.706s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.706s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.706s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.706s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.706s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.707s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/imu_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.707s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.707s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/control_feedback.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.707s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.708s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/encoder.py to encoder.cpython-312.pyc
-[1.709s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc
-[1.710s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/__init__.py to __init__.cpython-312.pyc
-[1.710s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[1.717s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc
-[1.720s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py to __init__.cpython-312.pyc
-[1.720s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py to realtime_location_cli_only.cpython-312.pyc
-[1.723s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py to graph_maker.cpython-312.pyc
-[1.725s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc
-[1.726s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py to imu_node.cpython-312.pyc
-[1.727s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc
-[1.729s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py to control_feedback.cpython-312.pyc
-[1.731s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py to uwb_pathing_node.cpython-312.pyc
-[1.733s] running install_data
-[1.733s] creating /home/robobin/robobin/ros2/install/robobin/share/ament_index
-[1.733s] creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index
-[1.733s] creating /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages
-[1.733s] copying resource/robobin -> /home/robobin/robobin/ros2/install/robobin/share/ament_index/resource_index/packages
-[1.733s] copying package.xml -> /home/robobin/robobin/ros2/install/robobin/share/robobin
-[1.733s] creating /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-[1.734s] copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-[1.734s] copying launch/robobin_no_components_launch.py -> /home/robobin/robobin/ros2/install/robobin/share/robobin/launch
-[1.735s] running install_egg_info
-[1.764s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[1.774s] running install_scripts
-[1.963s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.963s] Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.963s] Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.963s] Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.963s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.964s] Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.964s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.964s] Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.964s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.042s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-18_15-01-35/events.log b/ros2/log/build_2024-12-18_15-01-35/events.log
deleted file mode 100644
index 1b52721df991ad8c7dec5986054fa50e594ecb01..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_15-01-35/events.log
+++ /dev/null
@@ -1,56 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000298] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000769] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099641] (-) TimerEvent: {}
-[0.199945] (-) TimerEvent: {}
-[0.300216] (-) TimerEvent: {}
-[0.400611] (-) TimerEvent: {}
-[0.500902] (-) TimerEvent: {}
-[0.601137] (-) TimerEvent: {}
-[0.701369] (-) TimerEvent: {}
-[0.801632] (-) TimerEvent: {}
-[0.901894] (-) TimerEvent: {}
-[1.002175] (-) TimerEvent: {}
-[1.102413] (-) TimerEvent: {}
-[1.202687] (-) TimerEvent: {}
-[1.219088] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'SSH_CLIENT': '192.168.43.138 43375 22', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'tty', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin/ros2/src', 'SSH_TTY': '/dev/pts/0', 'ROS_PYTHON_VERSION': '3', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'XDG_SESSION_CLASS': 'user', 'TERM': 'xterm-256color', 'XDG_SESSION_ID': '4', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin', 'XDG_RUNTIME_DIR': '/run/user/1002', 'LANG': 'en_US.UTF-8', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'SSH_CONNECTION': '192.168.43.138 43375 192.168.43.18 22', 'XDG_DATA_DIRS': '/usr/share/gnome:/usr/local/share:/usr/share:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.302761] (-) TimerEvent: {}
-[1.403052] (-) TimerEvent: {}
-[1.503312] (-) TimerEvent: {}
-[1.591620] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.603385] (-) TimerEvent: {}
-[1.617933] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.618330] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.619351] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.620737] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.621873] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[1.678193] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.679422] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.679665] (robobin) StdoutLine: {'line': b'running build\n'}
-[1.679793] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[1.680089] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.681087] (robobin) StdoutLine: {'line': b'running install\n'}
-[1.690108] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[1.703449] (-) TimerEvent: {}
-[1.717136] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.718457] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[1.726215] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[1.726448] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[1.755091] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[1.755541] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[1.756699] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[1.803532] (-) TimerEvent: {}
-[1.903783] (-) TimerEvent: {}
-[1.944203] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.944491] (robobin) StdoutLine: {'line': b'Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.945827] (robobin) StdoutLine: {'line': b'Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.947185] (robobin) StdoutLine: {'line': b'Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.948615] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.951137] (robobin) StdoutLine: {'line': b'Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.952291] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.953615] (robobin) StdoutLine: {'line': b'Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.955501] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.003869] (-) TimerEvent: {}
-[2.034816] (robobin) CommandEnded: {'returncode': 0}
-[2.049236] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.051064] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-18_15-01-35/logger_all.log b/ros2/log/build_2024-12-18_15-01-35/logger_all.log
deleted file mode 100644
index fa88bbb9e8a46840bbe836856243725f88f4de21..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_15-01-35/logger_all.log
+++ /dev/null
@@ -1,137 +0,0 @@
-[0.153s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.154s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff86e31250>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff86e30f50>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff86e30f50>>, mixin_verb=('build',))
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.212s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.212s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.212s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.213s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.252s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.253s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.254s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.255s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.258s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.258s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.259s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.283s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.283s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.286s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/install
-[0.286s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.289s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.292s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.359s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.359s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.359s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.361s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.361s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.361s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.364s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.364s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.365s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.367s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.368s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.368s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.703s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.703s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.703s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.581s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.396s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.398s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.399s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.400s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.400s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.400s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.401s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.401s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.401s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.402s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.403s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.403s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.404s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.404s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.405s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.406s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.407s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.408s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.409s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.410s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.410s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.410s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.410s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.419s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.419s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.419s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.436s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.436s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.438s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.439s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.441s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[2.442s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[2.444s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[2.446s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[2.447s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[2.448s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[2.449s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-18_15-01-35/robobin/command.log b/ros2/log/build_2024-12-18_15-01-35/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_15-01-35/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-18_15-01-35/robobin/stderr.log b/ros2/log/build_2024-12-18_15-01-35/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-18_15-01-35/robobin/stdout.log b/ros2/log/build_2024-12-18_15-01-35/robobin/stdout.log
deleted file mode 100644
index f757cbdc8e497f58a9100ab20c788318dc367b88..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_15-01-35/robobin/stdout.log
+++ /dev/null
@@ -1,29 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-18_15-01-35/robobin/stdout_stderr.log b/ros2/log/build_2024-12-18_15-01-35/robobin/stdout_stderr.log
deleted file mode 100644
index f757cbdc8e497f58a9100ab20c788318dc367b88..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_15-01-35/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,29 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-18_15-01-35/robobin/streams.log b/ros2/log/build_2024-12-18_15-01-35/robobin/streams.log
deleted file mode 100644
index cd80b7cc37bb0579879d33fb031f4679feb76bd9..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_15-01-35/robobin/streams.log
+++ /dev/null
@@ -1,31 +0,0 @@
-[1.219s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[1.591s] running egg_info
-[1.617s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[1.617s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[1.618s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[1.620s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[1.621s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[1.677s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.678s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.679s] running build
-[1.679s] running build_py
-[1.679s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.680s] running install
-[1.689s] running install_lib
-[1.716s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.717s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[1.725s] running install_data
-[1.725s] running install_egg_info
-[1.754s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[1.754s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[1.756s] running install_scripts
-[1.943s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.943s] Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.945s] Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.946s] Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.948s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.950s] Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.951s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.953s] Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.954s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.034s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-18_16-49-48/events.log b/ros2/log/build_2024-12-18_16-49-48/events.log
deleted file mode 100644
index 8098d1aececfe62b2db8e06d73ac30cbd368bc9d..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_16-49-48/events.log
+++ /dev/null
@@ -1,61 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000287] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000738] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099662] (-) TimerEvent: {}
-[0.199983] (-) TimerEvent: {}
-[0.300266] (-) TimerEvent: {}
-[0.400523] (-) TimerEvent: {}
-[0.500853] (-) TimerEvent: {}
-[0.601127] (-) TimerEvent: {}
-[0.701421] (-) TimerEvent: {}
-[0.801656] (-) TimerEvent: {}
-[0.901932] (-) TimerEvent: {}
-[1.002255] (-) TimerEvent: {}
-[1.102538] (-) TimerEvent: {}
-[1.202853] (-) TimerEvent: {}
-[1.303153] (-) TimerEvent: {}
-[1.403440] (-) TimerEvent: {}
-[1.503738] (-) TimerEvent: {}
-[1.604044] (-) TimerEvent: {}
-[1.704343] (-) TimerEvent: {}
-[1.804616] (-) TimerEvent: {}
-[1.904969] (-) TimerEvent: {}
-[1.959017] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'SSH_CLIENT': '192.168.73.238 47996 22', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'tty', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin', 'SSH_TTY': '/dev/pts/0', 'ROS_PYTHON_VERSION': '3', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'COLCON_PREFIX_PATH': '/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'XDG_SESSION_CLASS': 'user', 'TERM': 'xterm-256color', 'XDG_SESSION_ID': '4', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin', 'XDG_RUNTIME_DIR': '/run/user/1002', 'LANG': 'en_US.UTF-8', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'SSH_CONNECTION': '192.168.73.238 47996 192.168.73.109 22', 'XDG_DATA_DIRS': '/usr/share/gnome:/usr/local/share:/usr/share:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[2.005054] (-) TimerEvent: {}
-[2.105375] (-) TimerEvent: {}
-[2.205708] (-) TimerEvent: {}
-[2.305952] (-) TimerEvent: {}
-[2.338905] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[2.365368] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[2.366520] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[2.367631] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[2.368281] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[2.368979] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.406028] (-) TimerEvent: {}
-[2.425558] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.427563] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.427822] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.427943] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.431711] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.441859] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.474077] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.476837] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.506104] (-) TimerEvent: {}
-[2.507779] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.508279] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.510244] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.606215] (-) TimerEvent: {}
-[2.702581] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.703589] (robobin) StdoutLine: {'line': b'Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.704339] (robobin) StdoutLine: {'line': b'Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.704971] (robobin) StdoutLine: {'line': b'Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.706272] (-) TimerEvent: {}
-[2.706528] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.707820] (robobin) StdoutLine: {'line': b'Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.709242] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.710708] (robobin) StdoutLine: {'line': b'Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[2.713761] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.795767] (robobin) CommandEnded: {'returncode': 0}
-[2.806356] (-) TimerEvent: {}
-[2.835447] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.836541] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-18_16-49-48/logger_all.log b/ros2/log/build_2024-12-18_16-49-48/logger_all.log
deleted file mode 100644
index b38edbdf5bd09121b99d5bb7ee8111da5e1d153f..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_16-49-48/logger_all.log
+++ /dev/null
@@ -1,136 +0,0 @@
-[0.616s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.616s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff9059cfb0>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff9059cce0>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff9059cce0>>, mixin_verb=('build',))
-[0.740s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.740s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.740s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.740s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.740s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.740s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.740s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.740s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.741s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.741s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.741s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.741s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.741s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.741s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.741s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.741s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.798s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.798s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.798s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.799s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.799s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.799s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.799s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.799s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.799s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.799s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.799s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.800s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.800s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.800s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.800s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.800s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.801s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.801s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.801s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.801s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.801s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.801s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.801s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.801s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.801s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.801s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.801s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.801s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.809s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.809s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.809s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.809s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.810s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.810s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.810s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.810s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.810s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.811s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.811s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.811s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.811s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.811s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.811s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.811s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.811s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.811s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.818s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.819s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.819s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.819s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.819s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.819s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.867s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.867s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.874s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.877s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.880s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.958s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.958s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.958s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.958s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.958s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.958s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.958s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.958s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.958s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.959s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.959s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.960s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.960s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.961s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.971s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.972s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.976s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.978s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.980s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.980s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.340s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[1.341s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[1.341s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[2.920s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[3.756s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[3.769s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[3.770s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[3.773s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[3.773s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[3.773s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[3.774s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[3.774s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[3.774s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[3.775s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[3.776s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[3.779s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[3.779s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[3.780s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[3.781s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[3.784s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[3.787s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[3.791s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[3.794s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[3.795s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[3.796s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[3.796s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[3.796s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[3.808s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[3.808s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[3.809s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[3.836s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[3.837s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[3.839s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[3.842s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[3.844s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[3.846s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[3.847s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[3.852s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[3.855s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[3.858s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[3.861s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-18_16-49-48/robobin/command.log b/ros2/log/build_2024-12-18_16-49-48/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_16-49-48/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-18_16-49-48/robobin/stderr.log b/ros2/log/build_2024-12-18_16-49-48/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-18_16-49-48/robobin/stdout.log b/ros2/log/build_2024-12-18_16-49-48/robobin/stdout.log
deleted file mode 100644
index 355022e982f9adc58436105b2d608023ffeb577d..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_16-49-48/robobin/stdout.log
+++ /dev/null
@@ -1,26 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-running install
-running install_lib
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-18_16-49-48/robobin/stdout_stderr.log b/ros2/log/build_2024-12-18_16-49-48/robobin/stdout_stderr.log
deleted file mode 100644
index 355022e982f9adc58436105b2d608023ffeb577d..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_16-49-48/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,26 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-running install
-running install_lib
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-18_16-49-48/robobin/streams.log b/ros2/log/build_2024-12-18_16-49-48/robobin/streams.log
deleted file mode 100644
index bc46c9a7776ba7245c9ae29ea643cc259e61a4a6..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_16-49-48/robobin/streams.log
+++ /dev/null
@@ -1,28 +0,0 @@
-[1.959s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.338s] running egg_info
-[2.365s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[2.366s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[2.367s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[2.368s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[2.368s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[2.425s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.427s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.427s] running build
-[2.427s] running build_py
-[2.431s] running install
-[2.441s] running install_lib
-[2.473s] running install_data
-[2.476s] running install_egg_info
-[2.507s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.508s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.510s] running install_scripts
-[2.702s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.703s] Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.704s] Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.704s] Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.706s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.707s] Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.709s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.710s] Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[2.713s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.795s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-18_22-30-58/events.log b/ros2/log/build_2024-12-18_22-30-58/events.log
deleted file mode 100644
index 388d46d0b83d2323bedd3b6b507e4e5b0434aba0..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_22-30-58/events.log
+++ /dev/null
@@ -1,62 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000271] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.001009] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099657] (-) TimerEvent: {}
-[0.199975] (-) TimerEvent: {}
-[0.300292] (-) TimerEvent: {}
-[0.400609] (-) TimerEvent: {}
-[0.500919] (-) TimerEvent: {}
-[0.601220] (-) TimerEvent: {}
-[0.701480] (-) TimerEvent: {}
-[0.801735] (-) TimerEvent: {}
-[0.902007] (-) TimerEvent: {}
-[1.002258] (-) TimerEvent: {}
-[1.102495] (-) TimerEvent: {}
-[1.202802] (-) TimerEvent: {}
-[1.214054] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'SSH_CLIENT': '192.168.73.238 48861 22', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'tty', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin', 'SSH_TTY': '/dev/pts/0', 'ROS_PYTHON_VERSION': '3', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'COLCON_PREFIX_PATH': '/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'XDG_SESSION_CLASS': 'user', 'TERM': 'xterm-256color', 'XDG_SESSION_ID': '17', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin', 'XDG_RUNTIME_DIR': '/run/user/1002', 'LANG': 'en_US.UTF-8', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'PWD': '/home/robobin/robobin/ros2/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'SSH_CONNECTION': '192.168.73.238 48861 192.168.73.109 22', 'XDG_DATA_DIRS': '/usr/share/gnome:/usr/local/share:/usr/share:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.302890] (-) TimerEvent: {}
-[1.403188] (-) TimerEvent: {}
-[1.503446] (-) TimerEvent: {}
-[1.591107] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.603517] (-) TimerEvent: {}
-[1.617451] (robobin) StdoutLine: {'line': b'writing ../../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.617875] (robobin) StdoutLine: {'line': b'writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.618926] (robobin) StdoutLine: {'line': b'writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.619539] (robobin) StdoutLine: {'line': b'writing requirements to ../../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.620291] (robobin) StdoutLine: {'line': b'writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt\n'}
-[1.674804] (robobin) StdoutLine: {'line': b"reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.675984] (robobin) StdoutLine: {'line': b"writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.676238] (robobin) StdoutLine: {'line': b'running build\n'}
-[1.676372] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[1.676673] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin\n'}
-[1.677375] (robobin) StdoutLine: {'line': b'copying robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers\n'}
-[1.677630] (robobin) StdoutLine: {'line': b'copying robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers\n'}
-[1.678152] (robobin) StdoutLine: {'line': b'running install\n'}
-[1.687303] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[1.703590] (-) TimerEvent: {}
-[1.714356] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.714781] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.715037] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.716123] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[1.726408] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py to realtime_location_cli_only.cpython-312.pyc\n'}
-[1.730290] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py to graph_maker.cpython-312.pyc\n'}
-[1.732655] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[1.732903] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[1.762056] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[1.762495] (robobin) StdoutLine: {'line': b'Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[1.763704] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[1.803685] (-) TimerEvent: {}
-[1.903945] (-) TimerEvent: {}
-[1.951549] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.951857] (robobin) StdoutLine: {'line': b'Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.953369] (robobin) StdoutLine: {'line': b'Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.955803] (robobin) StdoutLine: {'line': b'Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.956952] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.958275] (robobin) StdoutLine: {'line': b'Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.959621] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.962102] (robobin) StdoutLine: {'line': b'Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin\n'}
-[1.963733] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'\n"}
-[2.004066] (-) TimerEvent: {}
-[2.044318] (robobin) CommandEnded: {'returncode': 0}
-[2.058955] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.060211] (-) EventReactorShutdown: {}
diff --git a/ros2/log/build_2024-12-18_22-30-58/logger_all.log b/ros2/log/build_2024-12-18_22-30-58/logger_all.log
deleted file mode 100644
index 621aad227870cd3d4b8a01f193867eeed5300f48..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_22-30-58/logger_all.log
+++ /dev/null
@@ -1,136 +0,0 @@
-[0.150s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.150s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff89430b30>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff894307d0>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff894307d0>>, mixin_verb=('build',))
-[0.205s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.206s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.206s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.206s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.206s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.206s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.206s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2'
-[0.206s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.206s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.206s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.206s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.206s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.206s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.206s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.206s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.206s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.244s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ignore', 'ignore_ament_install']
-[0.245s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore'
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ignore_ament_install'
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_pkg']
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_pkg'
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['colcon_meta']
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'colcon_meta'
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['ros']
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'ros'
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['cmake', 'python']
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'cmake'
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python'
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extensions ['python_setup_py']
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src) by extension 'python_setup_py'
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extensions ['ignore', 'ignore_ament_install']
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) by extension 'ignore'
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src/build) ignored
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extensions ['ignore', 'ignore_ament_install']
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) by extension 'ignore'
-[0.246s] Level 1:colcon.colcon_core.package_identification:_identify(src/install) ignored
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extensions ['ignore', 'ignore_ament_install']
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) by extension 'ignore'
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(src/log) ignored
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore'
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ignore_ament_install'
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_pkg']
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_pkg'
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['colcon_meta']
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'colcon_meta'
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extensions ['ros']
-[0.247s] Level 1:colcon.colcon_core.package_identification:_identify(src/robobin) by extension 'ros'
-[0.250s] DEBUG:colcon.colcon_core.package_identification:Package 'src/robobin' with type 'ros.ament_python' and name 'robobin'
-[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.250s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.275s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.275s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.277s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.279s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.282s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.349s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.349s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.349s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.349s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.349s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.349s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.349s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.349s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.349s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.349s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.349s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.351s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.351s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.351s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.353s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.354s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.355s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.356s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.357s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.357s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.689s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.690s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.690s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.567s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.395s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[2.398s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake module files
-[2.398s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin' for CMake config files
-[2.399s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib'
-[2.399s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.399s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/pkgconfig/robobin.pc'
-[2.400s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages'
-[2.400s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.400s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.401s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.402s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.403s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/install/robobin/bin'
-[2.403s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.403s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.ps1'
-[2.405s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.dsv'
-[2.405s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.sh'
-[2.406s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.bash'
-[2.407s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/install/robobin/share/robobin/package.zsh'
-[2.408s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/install/robobin/share/colcon-core/packages/robobin)
-[2.409s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.410s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.410s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.410s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.418s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.418s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.418s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.437s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.437s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.ps1'
-[2.439s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_ps1.py'
-[2.440s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.ps1'
-[2.442s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.sh'
-[2.442s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/install/_local_setup_util_sh.py'
-[2.443s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.sh'
-[2.445s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.bash'
-[2.446s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.bash'
-[2.447s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/install/local_setup.zsh'
-[2.449s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/install/setup.zsh'
diff --git a/ros2/log/build_2024-12-18_22-30-58/robobin/command.log b/ros2/log/build_2024-12-18_22-30-58/robobin/command.log
deleted file mode 100644
index 077114c61b05aade2404b807da6e7addc796b9eb..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_22-30-58/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/build_2024-12-18_22-30-58/robobin/stderr.log b/ros2/log/build_2024-12-18_22-30-58/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/log/build_2024-12-18_22-30-58/robobin/stdout.log b/ros2/log/build_2024-12-18_22-30-58/robobin/stdout.log
deleted file mode 100644
index 61221a1cdeb24486f72d38f64eacc867b16a19c6..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_22-30-58/robobin/stdout.log
+++ /dev/null
@@ -1,35 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py to realtime_location_cli_only.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py to graph_maker.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-18_22-30-58/robobin/stdout_stderr.log b/ros2/log/build_2024-12-18_22-30-58/robobin/stdout_stderr.log
deleted file mode 100644
index 61221a1cdeb24486f72d38f64eacc867b16a19c6..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_22-30-58/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,35 +0,0 @@
-running egg_info
-writing ../../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-copying robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py to realtime_location_cli_only.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py to graph_maker.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
diff --git a/ros2/log/build_2024-12-18_22-30-58/robobin/streams.log b/ros2/log/build_2024-12-18_22-30-58/robobin/streams.log
deleted file mode 100644
index 8d72a19244536733e484e5fd56e37775a59ecbaa..0000000000000000000000000000000000000000
--- a/ros2/log/build_2024-12-18_22-30-58/robobin/streams.log
+++ /dev/null
@@ -1,37 +0,0 @@
-[1.215s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
-[1.590s] running egg_info
-[1.617s] writing ../../build/robobin/robobin.egg-info/PKG-INFO
-[1.617s] writing dependency_links to ../../build/robobin/robobin.egg-info/dependency_links.txt
-[1.618s] writing entry points to ../../build/robobin/robobin.egg-info/entry_points.txt
-[1.619s] writing requirements to ../../build/robobin/robobin.egg-info/requires.txt
-[1.619s] writing top-level names to ../../build/robobin/robobin.egg-info/top_level.txt
-[1.674s] reading manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.675s] writing manifest file '../../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.675s] running build
-[1.675s] running build_py
-[1.676s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin
-[1.676s] copying robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-[1.677s] copying robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers
-[1.677s] running install
-[1.686s] running install_lib
-[1.713s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin
-[1.714s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.714s] copying /home/robobin/robobin/ros2/build/robobin/build/lib/robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.715s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[1.726s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py to realtime_location_cli_only.cpython-312.pyc
-[1.729s] byte-compiling /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py to graph_maker.cpython-312.pyc
-[1.732s] running install_data
-[1.732s] running install_egg_info
-[1.761s] removing '/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[1.762s] Copying ../../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[1.763s] running install_scripts
-[1.951s] Installing api_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.951s] Installing control_feedback script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.952s] Installing encoder_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.955s] Installing imu_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.956s] Installing motor_control_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.957s] Installing motor_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.959s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.961s] Installing uwb_pathing_node script to /home/robobin/robobin/ros2/install/robobin/lib/robobin
-[1.963s] writing list of installed files to '/home/robobin/robobin/ros2/build/robobin/install.log'
-[2.044s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../../build/robobin build --build-base /home/robobin/robobin/ros2/build/robobin/build install --record /home/robobin/robobin/ros2/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/log/latest b/ros2/log/latest
deleted file mode 120000
index b57d247c77c0293269460b70b9bb1360f27cf808..0000000000000000000000000000000000000000
--- a/ros2/log/latest
+++ /dev/null
@@ -1 +0,0 @@
-latest_build
\ No newline at end of file
diff --git a/ros2/log/latest_build b/ros2/log/latest_build
deleted file mode 120000
index 11f21c604a39a589b2aeac2963897b710483acae..0000000000000000000000000000000000000000
--- a/ros2/log/latest_build
+++ /dev/null
@@ -1 +0,0 @@
-build_2024-12-16_16-30-47
\ No newline at end of file
diff --git a/ros2/src/build/.built_by b/ros2/src/build/.built_by
deleted file mode 100644
index 06e74acb63e6917bd1f0f8853213d49f0c5978e4..0000000000000000000000000000000000000000
--- a/ros2/src/build/.built_by
+++ /dev/null
@@ -1 +0,0 @@
-colcon
diff --git a/ros2/src/build/COLCON_IGNORE b/ros2/src/build/COLCON_IGNORE
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/build/robobin/build/lib/robobin/__init__.py b/ros2/src/build/robobin/build/lib/robobin/__init__.py
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/build/robobin/build/lib/robobin/api_node.py b/ros2/src/build/robobin/build/lib/robobin/api_node.py
deleted file mode 100644
index d83622c7d0d85e12c642f1fad0dfe9b411b6dd60..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/build/lib/robobin/api_node.py
+++ /dev/null
@@ -1,106 +0,0 @@
-
-# robobin/api_node.py
-from .helpers.message_handler import MessageHandler
-from .helpers.connection_manager import ConnectionManager
-
-from geometry_msgs.msg import Twist
-from geometry_msgs.msg import Point
-from std_msgs.msg import String
-import rclpy
-from rclpy.node import Node
-
-class ApiNode(Node):
-    def __init__(self):
-        super().__init__('api_node')
-        self.get_logger().info("ApiNode has been started.")
-
-        self.publisher_topics = {
-            "cmd_vel": self.create_publisher(Twist, '/cmd_vel', 10),
-            "nav_send": self.create_publisher(Twist, '/nav_send', 10), 
-            "nav_command": self.create_publisher(String, '/nav_command', 10),
-        }
-        self.location_subscriber = self.create_subscription(
-            Point,  # Message type
-            '/tag1_location',  # Topic
-            self.handle_location_update,  # Callback
-            10  # QoS depth
-        )
-        self.mode = "Manual"
-        self.called_locations = [] # List of  pairs of ip address and location
-        self.message_handler = MessageHandler(self)
-        self.connection_manager = ConnectionManager(self)
-
-        self.connection_manager.start()
-        self.get_logger().info("Connection manager started.")
-    def handle_client_connection(self, client_socket):
-        """Handles incoming TCP client connections."""
-        try:
-            while True:
-                data = client_socket.recv(1024).decode()
-                if not data:
-                    break
-                self.get_logger().info(f"Received data: {data}")
-                test = data.split(" ", 1)
-                self.get_logger().info(f"Received command: {test[0]}")
-                result = self.message_handler.handle_message(client_socket, data)
-        
-                # Check if the result is not None
-                if result is not None:
-                    topic, message = result  # Safely unpack after checking
-                    if topic is not None:
-                        self.get_logger().info(f"Publishing to topic: {topic}")
-                        self.publish_to_topic(topic, message)
-        finally:
-            client_socket.close()
-            self.get_logger().info("Client disconnected.")
-    def publish_to_topic(self, topic, message):
-        self.get_logger().info(f"Publishing to topic: {topic}")
-        """Publishes the message to the specified topic."""
-        if topic in self.publisher_topics:
-            publisher = self.publisher_topics[topic]
-
-            # Check if the topic is 'cmd_vel' and format the message as a Twist message
-            if topic == "cmd_vel" and isinstance(message, tuple):
-                linear_x, angular_z = message
-                twist_msg = Twist()
-                twist_msg.linear.x = linear_x
-                twist_msg.linear.y = 0.0
-                twist_msg.linear.z = 0.0
-                twist_msg.angular.x = 0.0
-                twist_msg.angular.y = 0.0
-                twist_msg.angular.z = angular_z
-
-                publisher.publish(twist_msg)
-                self.get_logger().info(f"Published to {topic}: linear_x={linear_x}, angular_z={angular_z}")
-            elif topic == "nav_command" and isinstance(message, str):
-                self.get_logger().info(f"Published to {topic}: {message}")
-                publisher.publish(String(data=message))
-            else:
-                self.get_logger().warning(f"Unhandled message type for topic: {topic}")
-        else:
-            self.get_logger().warning(f"Unknown topic: {topic}")
-    def handle_location_update(self, msg):
-        self.get_logger().info("Received updated location.")
-        self.get_logger().info(f"Received updated location: x={msg.x:.2f}, y={msg.y:.2f}")
-        """Callback for the /tag1_location topic."""
-        x = msg.x
-        y = msg.y
-        self.connection_manager.set_location(x, y)
-        self.get_logger().info(f"Received updated location: x={x:.2f}, y={y:.2f}")
-    def shutdown(self):
-        """Stops the connection manager."""
-        self.connection_manager.stop()
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = ApiNode()
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        node.shutdown()
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/src/build/robobin/build/lib/robobin/control_feedback.py b/ros2/src/build/robobin/build/lib/robobin/control_feedback.py
deleted file mode 100644
index 78a1edb74b03fbdf991c9e38c1b8980ee52b3945..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/build/lib/robobin/control_feedback.py
+++ /dev/null
@@ -1,320 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Twist
-from std_msgs.msg import Int64, Float64
-from gpiozero import PWMOutputDevice, DigitalOutputDevice
-import time
-from rclpy.clock import Clock
-from rclpy.time import Time
-import bisect
-
-
-
-# Example of how you could implement a simple PID controller
-class PIDController:
-    def __init__(self, kp, ki, kd):
-        self.kp = kp
-        self.ki = ki
-        self.kd = kd
-        self.prev_error = 0
-        self.integral = 0
-
-    def reset(self):
-        self.prev_error = 0
-        self.integral = 0
-
-    def calculate(self, error, dt):
-        self.integral += error * dt
-        derivative = (error - self.prev_error) / dt 
-        output = self.kp * error + self.ki * self.integral + self.kd * derivative
-        self.prev_error = error
-        return output
-
-
-
-
-class MotorControlNode(Node):
-    def __init__(self):
-        super().__init__('control_feedback_node')
-
-        # Initialize encoder values
-        self.encoder_left_steps = 0
-        self.encoder_right_steps = 0
-
-        # Desired speeds from cmd_vel
-        self.desired_linear_speed = 0.0
-        self.desired_angular_speed = 0.0
-
-        self.prev_left_steps = 0
-        self.prev_right_steps = 0
-
-        self.left_pwm = 0
-        self.right_pwm = 0
-
-        self.prev_desired_speed = 0.0
-
-
-        #Time
-        self.prev_time = time.time()
-        #self.prev_time = self.get_clock().now
-
-        
-        # Robot parameters
-        self.wheel_base = 0.40  
-        self.encoder_steps_per_rotation = 310  
-        self.wheel_radius = 0.075 
-
-        # Initialize the motors
-        self.motor = Motor(self,14,15,18, 17, 22, 27)
-
-        # PID controllers
-        self.pid_left_forward = PIDController(kp=0.5, ki=0.0, kd=0.001)
-        self.pid_right_forward = PIDController(kp=0.525, ki=0.0, kd=0.001)
-
-        self.pid_left_backward = PIDController(kp=0.525, ki=0.0, kd=0.001)
-        self.pid_right_backward = PIDController(kp=0.5, ki=0.0, kd=0.001)
-
-
-
-
-        # Subscribe to cmd_vel topic
-        self.subscription = self.create_subscription(
-            Twist,
-            '/cmd_vel',
-            self.cmd_vel_callback,
-            10
-        )
-
-        # Subscribe to encoder data
-        self.left_encoder_sub = self.create_subscription(
-            Int64,
-            'left_wheel_steps',
-            self.left_encoder_callback,
-            10
-        )
-        self.right_encoder_sub = self.create_subscription(
-            Int64,
-            'right_wheel_steps',
-            self.right_encoder_callback,
-            10
-        )
-
-        self.left_actual_speed_pub = self.create_publisher(Float64, 'left_actual_wheel_speed', 10)
-        self.right_actual_speed_pub = self.create_publisher(Float64, 'right_actual_wheel_speed', 10)
-        self.desired_speed_pub = self.create_publisher(Float64, 'desired_wheel_speed', 10)
-
-        # Timer to update motor speeds
-        self.control_timer = self.create_timer(0.1, self.control_loop)
-
-        self.get_logger().info('Motor control node with encoder feedback has been started.')
-
-    def cmd_vel_callback(self, msg):
-        # Store desired speeds
-        self.desired_linear_speed = msg.linear.x  # Forward/backward speed
-        self.desired_angular_speed = msg.angular.z  # Turning rate
-
-        # if (self.desired_linear_speed >= 0 and self.prev_desired_speed < 0) or (self.desired_linear_speed < 0 and self.prev_desired_speed >= 0):
-
-        #     self.pid_left_forward.reset()
-        #     self.pid_right_forward.reset()
-        #     self.pid_left_backward.reset()
-        #     self.pid_right_backward.reset()
-
-
-
-        
-
-        self.prev_desired_speed = self.desired_linear_speed
-
-    def left_encoder_callback(self, msg):
-        self.encoder_left_steps = msg.data
-
-    def right_encoder_callback(self, msg):
-        self.encoder_right_steps = msg.data
-
-    
-    def control_loop(self):
-
-        if self.desired_linear_speed >= 0:
-            # Forward motion
-            left_pid = self.pid_left_forward
-            right_pid = self.pid_right_forward
-        else:
-            # Backward motion
-            left_pid = self.pid_left_backward
-            right_pid = self.pid_right_backward
-
-        if (self.desired_linear_speed == 0) and (self.desired_angular_speed == 0):
-            self.stop_motors()
-            self.pid_left_forward.reset()
-            self.pid_right_forward.reset()
-            self.pid_left_backward.reset()
-            self.pid_right_backward.reset()
-            self.left_pwm =0
-            self.right_pwm =0
-            return
-
-
-
-
-        #Calculate the actual speed
-        #-------------------------------
-        # Calculate elapsed time
-        current_time = time.time()
-        #dt = current_time - self.prev_time
-        dt = max(current_time - self.prev_time, 0.01)  # Prevent dt from being too small
-        #dt = max(current_time - self.prev_time, 1e-6)  # Avoid zero or too small dt
-        if dt == 0:
-            return
-        self.prev_time = current_time
-
-        # self.prev_time = self.get_clock().now()
-        # current_time = self.get_clock().now()
-        # dt = (current_time - self.prev_time).to_sec()
-        # if dt <= 0.0:
-        #     return
-        # self.prev_time = current_time
-
-        #Actual Speed calculation
-        #------------------------------------
-        # Calculate change in encoder steps
-        delta_left_steps = self.encoder_left_steps - self.prev_left_steps
-        delta_right_steps = self.encoder_right_steps - self.prev_right_steps
-
-        self.prev_left_steps = self.encoder_left_steps
-        self.prev_right_steps = self.encoder_right_steps
-
-        # Calculate rotational speeds (RPS)
-        left_rps = delta_left_steps / (self.encoder_steps_per_rotation * dt)
-        right_rps = delta_right_steps / (self.encoder_steps_per_rotation * dt)
-
-        # Convert to linear speed (m/s)
-        left_speed_actual = left_rps * 2 * 3.14159 * self.wheel_radius
-        right_speed_actual = right_rps * 2 * 3.14159 * self.wheel_radius
-
-
-
-        #Desired Speed calculation
-        #------------------------------------
-        # Desired speeds for left and right wheels
-        left_speed_desired = self.desired_linear_speed - (self.desired_angular_speed * self.wheel_base / 2.0)
-        right_speed_desired = self.desired_linear_speed + (self.desired_angular_speed * self.wheel_base / 2.0)
-
-
-
-        # Speed Errors calculation
-        #------------------------------------
-        left_error = left_speed_desired - left_speed_actual
-        right_error = right_speed_desired - right_speed_actual
-
- 
-
-        # Use PID controllers for left and right wheels
-        left_pwm_error = left_pid.calculate(left_error, dt)
-        right_pwm_error = right_pid.calculate(right_error, dt)
-
-        self.left_pwm +=   left_pwm_error
-        self.right_pwm +=  right_pwm_error
-
-
-
-        # Ensure PWM values are within [-1, 1]
-        left_pwm = max(-1, min(1, self.left_pwm))
-        right_pwm = max(-1, min(1, self.right_pwm))
-
-        # Apply PWM values to motors
-        self.motor.set_pwm(left_pwm, right_pwm)
-
-        
-
-
-        # Publish actual speeds
-        left_actual_speed_msg = Float64()
-        left_actual_speed_msg.data = left_speed_actual
-        self.left_actual_speed_pub.publish(left_actual_speed_msg)
-
-        right_actual_speed_msg = Float64()
-        right_actual_speed_msg.data = right_speed_actual
-        self.right_actual_speed_pub.publish(right_actual_speed_msg)
-
-        desired_speed_msg = Float64()
-        desired_speed_msg.data = right_speed_desired
-        self.desired_speed_pub.publish(desired_speed_msg)
-
-
-        # Debugging info
-        # self.get_logger().info(f'Left PWM IN: {self.left_pwm:.2f}, Right PWM IN: {right_pwm:.2f}')
-        # self.get_logger().info(f'Left Speed Actual: {left_speed_actual:.2f}, Right Speed Actual: {right_speed_actual:.2f}')
-        # self.get_logger().info(f'Left Error: {left_error:.2f}, Right Error: {left_pwm_error:.2f}')
-        # self.get_logger().info(f'Left_speed_desired: {left_speed_desired:.2f}, Right_speed_desired: {right_speed_desired:.2f}')
-        # self.get_logger().info('-----------------------------------------------------------------')
-
-
-    def stop_motors(self):
-        self.motor.stop()
-        # self.get_logger().info('Motors have been stopped.')
-
-class Motor:
-    def __init__(self,node, EnaA, In1A, In2A, EnaB, In1B, In2B):
-
-        self.node = node
-        # Left motor control pins
-        self.pwmA = PWMOutputDevice(EnaA)
-        self.in1A = DigitalOutputDevice(In1A)
-        self.in2A = DigitalOutputDevice(In2A)
-
-        # Right motor control pins
-        self.pwmB = PWMOutputDevice(EnaB)
-        self.in1B = DigitalOutputDevice(In1B)
-        self.in2B = DigitalOutputDevice(In2B)
-
-    def set_pwm(self, left_pwm, right_pwm):
-
-        #Deadband to prevent the motors from responding to very small PWM values that could cause jitter.
-        DEADZONE = 0.002
-
-        if abs(left_pwm) < DEADZONE:
-            self.pwmA.value = 0
-            self.in1A.off()
-            self.in2A.off()
-        else:
-            self.pwmA.value = abs(left_pwm)
-            self.in1A.value = left_pwm >  0
-            self.in2A.value = left_pwm < 0
-
-        if abs(right_pwm) < DEADZONE:
-            self.pwmB.value = 0
-            self.in1B.off()
-            self.in2B.off()
-        else:
-            self.pwmB.value = abs(right_pwm)
-            self.in1B.value = right_pwm >  0
-            self.in2B.value = right_pwm < 0
-
-        #self.node.get_logger().info(f"Left Motor PWM: Speed={left_pwm}, Right Motor PWM: Speed={right_pwm}")
-
-    def stop(self):
-        # Stop both motors
-        self.pwmA.value = 0
-        self.pwmB.value = 0
-        self.in1A.off()
-        self.in2A.off()
-        self.in1B.off()
-        self.in2B.off()
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = MotorControlNode()
-
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.stop_motors()
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/src/build/robobin/build/lib/robobin/encoder.py b/ros2/src/build/robobin/build/lib/robobin/encoder.py
deleted file mode 100644
index f646d3dc16cc781b870f52bdbbfc5b5e6e3cbcd0..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/build/lib/robobin/encoder.py
+++ /dev/null
@@ -1,63 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from std_msgs.msg import Int64
-from gpiozero import RotaryEncoder, InputDevice
-
-
-
-class EncoderReaderNode(Node):
-    def __init__(self):
-        super().__init__('encoder_reader_node')
-
-        motor1A = 5
-        motor1B = 6
-        motor2A = 20
-        motor2B = 21
-
-        self.encoder_left = RotaryEncoder(a = motor1A,b = motor1B, max_steps=0)
-        self.encoder_right = RotaryEncoder(a = motor2A,b = motor2B, max_steps=0)
-
-        # Publishers for encoder steps
-        self.left_encoder_pub = self.create_publisher(Int64, 'left_wheel_steps', 10)
-        self.right_encoder_pub = self.create_publisher(Int64, 'right_wheel_steps', 10)
-
-        # Timer to read encoders
-        self.timer = self.create_timer(0.1, self.publish_encoder_steps)
-
-        self.get_logger().info('Encoder reader node has been started.')
-
-    def publish_encoder_steps(self):
-        # Read encoder steps
-        left_steps = self.encoder_left.steps
-        right_steps = -(self.encoder_right.steps)
-
-        # Create messages
-        left_msg = Int64()
-        left_msg.data = left_steps
-
-        right_msg = Int64()
-        right_msg.data = right_steps
-
-        # Publish messages
-        self.left_encoder_pub.publish(left_msg)
-        self.right_encoder_pub.publish(right_msg)
-
-        # Log the steps
-        #self.get_logger().info(f'Left Steps: {left_steps}, Right Steps: {right_steps}')
-
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = EncoderReaderNode()
-
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/src/build/robobin/build/lib/robobin/helpers/__init__.py b/ros2/src/build/robobin/build/lib/robobin/helpers/__init__.py
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/build/robobin/build/lib/robobin/helpers/connection_manager.py b/ros2/src/build/robobin/build/lib/robobin/helpers/connection_manager.py
deleted file mode 100644
index 0fb010b26ca2d962796eb49eee48ab8836705d9f..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/build/lib/robobin/helpers/connection_manager.py
+++ /dev/null
@@ -1,88 +0,0 @@
-import socket
-import threading
-import time
-import json
-
-class ConnectionManager:
-    def __init__(self, api_node, udp_ip="255.255.255.255", udp_port=5005, listen_port=5006):
-        self.api_node = api_node
-        self.UDP_IP = udp_ip
-        self.UDP_PORT = udp_port
-        self.LISTEN_PORT = listen_port
-        self.stop_event = threading.Event()
-        self.location = [0, 0]  # At some point, this will be retrieved from the navigation node
-                
-    def start(self):
-        """Starts listening for connections and broadcasting presence."""
-        self.listen_thread = threading.Thread(target=self.listen_for_connections)
-        self.broadcast_thread = threading.Thread(target=self.broadcast_presence)
-        self.listen_thread.start()
-        self.broadcast_thread.start()
-
-    def listen_for_connections(self):
-        """Listens for UDP 'CONNECT' messages and sets up TCP connections."""
-        udp_sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
-        udp_sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
-        udp_sock.bind(('', self.LISTEN_PORT))
-
-        while not self.stop_event.is_set():
-            try:
-                data, addr = udp_sock.recvfrom(1024)
-                if data.decode() == "CONNECT":
-                    self.api_node.get_logger().info(f"Received CONNECT message from {addr}")
-                    tcp_sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
-                    tcp_sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
-                    tcp_sock.bind(('', self.LISTEN_PORT))
-                    tcp_sock.listen(1)
-                    client_socket, client_addr = tcp_sock.accept()
-                    self.api_node.get_logger().info(f"Client connected from {client_addr}")
-                    threading.Thread(target=self.api_node.handle_client_connection, args=(client_socket,)).start()
-            except socket.timeout:
-                continue
-            except OSError:
-                break
-
-        udp_sock.close()
-        print("Stopped listening for connections.")
-
-    def broadcast_presence(self):
-        """Broadcasts presence periodically over UDP."""
-        sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
-        sock.setsockopt(socket.SOL_SOCKET, socket.SO_BROADCAST, 1)
-
-        while not self.stop_event.is_set():
-            try:
-                mode = self.api_node.mode
-                
-                # JSON-formatted message
-                message = {
-                    "type": "ROBOBIN_PRESENT",
-                    "data": {
-                        "Location": self.location,
-                        "Mode": mode,
-                       
-                    }
-                }
-
-                # Serialize the JSON message to a string
-                json_message = json.dumps(message).encode('utf-8')
-
-                # Send the JSON message over UDP
-                sock.sendto(json_message, (self.UDP_IP, self.UDP_PORT))
-                self.api_node.get_logger().info("Broadcasting JSON presence.")
-                self.api_node.get_logger().info(f"Location: {self.location}, Mode: {mode}")
-                time.sleep(2)
-            except OSError:
-                break
-
-        sock.close()
-        self.api_node.get_logger().info("Stopped broadcasting presence.")
-    def set_location(self, x, y):
-        """Sets the location of the robot."""
-        self.location = [x, y]
-    def stop(self):
-        """Stops the connection manager."""
-        self.stop_event.set()
-    
-if __name__ == "__main__":
-    ConnectionManager(None).start()
diff --git a/ros2/src/build/robobin/build/lib/robobin/helpers/graph_maker.py b/ros2/src/build/robobin/build/lib/robobin/helpers/graph_maker.py
deleted file mode 100644
index c197c10b7eea1a63721b6cf40554a57b79c13d75..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/build/lib/robobin/helpers/graph_maker.py
+++ /dev/null
@@ -1,112 +0,0 @@
-import json
-import time
-import os
-from realtime_location_cli_only import AnchorTagCLI
-
-class GraphMaker:
-    def __init__(self, port="COM11", testing=False):
-        self.app = AnchorTagCLI(port=port, testing=testing)
-        self.graph = {
-            "name": "Lab 1 Extended",
-            "nodes": [],
-            "connections": []
-        }
-        self.previous_node_index = None
-
-    def call_bpm_and_store_anchors(self):
-        self.app.call_bpm()
-        for name, (x, y) in self.app.anchors.items():
-            self.graph["nodes"].append({
-                "name": name,
-                "x": x,
-                "y": y
-            })
-
-        # Initialize connections matrix with False
-        num_nodes = len(self.graph["nodes"])
-        self.graph["connections"] = [[False] * num_nodes for _ in range(num_nodes)]
-
-        print("Anchor coordinates stored successfully.")
-
-    def start_session(self):
-        print("Waiting for 'start' command...")
-        while True:
-            user_input = input("Enter 'start' to begin adding nodes or 'quit' to exit: ").strip().lower()
-            if user_input == "start":
-                print("Session started. Type 'save' to add nodes, 'finish' to save the graph, or 'quit' to exit.")
-                break
-            elif user_input == "quit":
-                print("Exiting...")
-                exit()
-
-    def add_node_and_connect(self):
-        print(self.app.tag_distances)
-        distances = self.app.serial_buffer.getRangingDistances()
-
-        tag1_x, tag1_y = self.app.update_distances_and_calculate_tags()
-        print(f"{tag1_x}, {tag1_y}")
-        if tag1_x is None or tag1_y is None:
-            print("Failed to determine tag position. Skipping node creation.")
-            return
-
-        new_node_index = len(self.graph["nodes"])
-
-        # Add new node
-        self.graph["nodes"].append({
-            "name": f"Node{new_node_index+1}",
-            "x": tag1_x,
-            "y": tag1_y
-        })
-
-        # Dynamically resize the connections matrix
-        for row in self.graph["connections"]:
-            row.append(False)  # Add a column for the new node
-        self.graph["connections"].append([False] * (new_node_index + 1))  # Add a new row
-
-        # Update connections
-        if self.previous_node_index is not None:
-            self.graph["connections"][self.previous_node_index][new_node_index] = True
-            self.graph["connections"][new_node_index][self.previous_node_index] = True
-
-        self.previous_node_index = new_node_index
-
-        print(f"Node {new_node_index+1} added at ({tag1_x:.2f}, {tag1_y:.2f}).")
-
-    def save_graph(self):
-        directory = r"D:\Github\robobin\ros2\src\robobin\robobin\graphs" #Replace with whereever your graphs folder is in the ros2 workspace
-        os.makedirs(directory, exist_ok=True)  # Create the directory if it doesn't exist
-        file_path = os.path.join(directory, "graph.json")
-        with open(file_path, "w") as f:
-            json.dump(self.graph, f, indent=2)
-        print(f"Graph saved to '{file_path}'.")
-
-
-    def run(self):
-        while True:
-            user_input = input("Enter command ('bpm', 'start', 'save', 'finish', 'quit'): ").strip().lower()
-            if user_input == "bpm":
-                self.call_bpm_and_store_anchors()
-            elif user_input == "start":
-                self.start_session()
-                while True:
-                    user_input = input("Enter 'save' to add a node, 'finish' to save and exit, or 'quit' to exit: ").strip().lower()
-                    if user_input == "save":
-                        self.add_node_and_connect()
-                    elif user_input == "finish":
-                        self.save_graph()
-                        print("Session finished.")
-                        exit()
-                    elif user_input == "quit":
-                        print("Exiting without saving.")
-                        exit()
-                    else:
-                        print("Invalid command. Try 'save', 'finish', or 'quit'.")
-            elif user_input == "quit":
-                print("Exiting...")
-                break
-            else:
-                print("Invalid command. Try 'bpm', 'start', 'save', 'finish', or 'quit'.")
-
-if __name__ == "__main__":
-    graph_maker = GraphMaker(port="/dev/tty.usbmodem14101", testing=False)
-    graph_maker.run()
diff --git a/ros2/src/build/robobin/build/lib/robobin/helpers/message_handler.py b/ros2/src/build/robobin/build/lib/robobin/helpers/message_handler.py
deleted file mode 100644
index 72ca4a5795a8a5190e77e67e41b42bfa8d4e3a11..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/build/lib/robobin/helpers/message_handler.py
+++ /dev/null
@@ -1,193 +0,0 @@
-# robobin/message_handler.py
-import time
-import json
-
-import os
-class MessageHandler:
-    def __init__(self, api_node, testing=False):
-        self.api_node = api_node
-        self.testing = testing
-        self.handlers = {
-            "PING": self.handle_ping,
-            "TIME": self.handle_time_request,
-            "MANUALCTRL": self.handle_manual_control,
-            "SETMODE": self.handle_set_mode,
-            "STOP": self.handle_stop,
-            "CALLME": self.handle_call_me,
-            "BPM": self.handle_call_bpm,
-            "REQMAP": self.handle_request_map,
-        }
-
-    def handle_message(self, client_socket, raw_message):
-        """Parses the incoming message and routes the command to the appropriate handler."""
-        command, *args = raw_message.split(" ", 1)
-        #self.api_node.logger.info(f"Received command: {command}")
-        #self.api_node.logger.info(f"Received arguments: {args}")
-        data = args[0] if args else None
-        handler = self.handlers.get(command, self.handle_unknown_message)
-        return handler(client_socket, data)
-    
-    def handle_call_me(self, client_socket, message):
-        #Message says  CALLME,(212.9638, 283.98108), extract location and ip address
-        if client_socket is None:
-            ip = "Fake IP"
-        else:
-            ip = client_socket.getpeername()[0]
-        print(message)
-        location = message.strip() # Remove parentheses
-        location = f"{location}"  # Add parentheses back for proper formatting
-        
-        for existing_ip, _ in self.api_node.called_locations:
-            if existing_ip == ip:
-                client_socket.sendall(b"User already requested location")
-                return None  # IP already in the list, exit early
-
-        self.api_node.called_locations.append((ip, location))
-    
-        response = f"Queue Position = {len(self.api_node.called_locations)-1}".encode()
-        client_socket.sendall(response)
-        print("nav_command", location)
-        return "nav_command", location
-    
-    def handle_stop(self, client_socket, _):
-        """Handles the STOP command."""
-        response = b"Stopping the robot"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        return "cmd_vel", (0.0, 0.0)
-    
-    def handle_ping(self, client_socket, _):
-        """Responds with a PONG message."""
-        response = b"PONG"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-
-        return None
-    def handle_set_mode(self, client_socket, message):
-        """Handles mode setting commands."""
-        response = f"Setting mode to {message}".encode()
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        self.api_node.mode = message
-        return None
-    def handle_time_request(self, client_socket, _):
-        """Sends the current server time."""
-        response = time.ctime().encode()
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-
-        return None
-    def handle_call_bpm(self, client_socket, _):
-        """Handles the CALLBPM command."""
-        response = b"Calling BPM, Graph will be reset"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-
-        return "nav_command","BPM"
-    def handle_manual_control(self, client_socket, message):
-        """Handles manual control commands: W, A, S, D."""
-        # W: linear.x = 0.5, angular.z = 0
-        # A: linear.x = 0, angular.z = 0.5
-        # S: linear.x = -0.5, angular.z = 0
-        # D: linear.x = 0, angular.z = -0.5
-        
-        directions = {
-            "W": (0.5, 0),    # Move forward
-            "A": (0, 0.5),    # Turn left
-            "S": (-0.5, 0),   # Move backward
-            "D": (0, -0.5)    # Turn right
-        }
-        
-        # Get direction data and ensure it's a tuple of floats
-        raw_response_data = directions.get(message.strip().upper(), (0, 0))
-        response_data = (float(raw_response_data[0]), float(raw_response_data[1]))  # Explicitly cast to float
-        
-        # Send feedback to the client
-        response = f"Manual control command received: {response_data}".encode()
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        
-        print("Processed manual control command:", response_data)
-        return "cmd_vel", response_data
-
-    def handle_request_map(self, client_socket, _):
-            """Handles the REQMAP command."""
-            # Relative path to the JSON file
-            graph_file_path = os.path.join("src", "robobin", "robobin", "graphs", "graph.json")
-
-            try:
-                # Load the graph JSON file
-                with open(graph_file_path, 'r') as f:
-                    graph_data = json.load(f)
-
-                # Serialize the JSON data to a string
-                graph_json = json.dumps(graph_data)
-                # Send the JSON response back to the client
-                if self.testing:
-                    print("Sending map data:", graph_json)
-                else:
-                    client_socket.sendall(graph_json.encode())
-
-                return None
-
-            except FileNotFoundError:
-                error_message = f"Error: File not found at {graph_file_path}"
-                if self.testing:
-                    print(error_message)
-                else:
-                    client_socket.sendall(error_message.encode())
-
-                return None
-
-            except json.JSONDecodeError as e:
-                error_message = f"Error: Failed to decode JSON - {str(e)}"
-                if self.testing:
-                    print(error_message)
-                else:
-                    client_socket.sendall(error_message.encode())
-
-                return None
-
-            except Exception as e:
-                error_message = f"Error: {str(e)}"
-                if self.testing:
-                    print(error_message)
-                else:
-                    client_socket.sendall(error_message.encode())
-
-                return None
-    def handle_unknown_message(self, client_socket, _):
-        """Handles unknown commands."""
-        response = b"Unknown command"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        return None
-    
-# Test class without api_node and with testing enabled
-if __name__ == "__main__":
-    message_handler = MessageHandler(None, testing=True)
-    assert message_handler.handle_message(None, "PING") is None
-    assert message_handler.handle_message(None, "TIME") is None
-    assert message_handler.handle_message(None, "MANUALCTRL W") == ("cmd_vel", (0.5, 0))
-    assert message_handler.handle_message(None, "MANUALCTRL A") == ("cmd_vel", (0, 0.5))
-    assert message_handler.handle_message(None, "MANUALCTRL S") == ("cmd_vel", (-0.5, 0))
-    assert message_handler.handle_message(None, "MANUALCTRL D") == ("cmd_vel", (0, -0.5))
-
-    assert message_handler.handle_message(None, "STOP") == ("cmd_vel", (0.0, 0.0))
-    assert message_handler.handle_message(None, "CALLME (212.9638, 283.98108)") == ("nav_command", "(212.9638, 283.98108)")
-    assert message_handler.handle_message(None, "UNKNOWN") is None
-    assert message_handler.handle_message(None, "REQMAP") is None
\ No newline at end of file
diff --git a/ros2/src/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py b/ros2/src/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py
deleted file mode 100644
index a314cec3db27597e1303cf8ca2d0a00523600dbe..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py
+++ /dev/null
@@ -1,263 +0,0 @@
-import time
-import numpy as np
-import serial
-from scipy.optimize import least_squares
-
-# Define test values at the top of the file for easy modification
-TEST_MEASURED_DISTANCES = [302, 463, 286, 304, 418, 328]
-TEST_TAG1_DISTANCES = [22, 107, 246, 295]
-TEST_TAG2_DISTANCES = [100, 100, 100, 100]
-
-class SerialBuffer:
-    def __init__(self, port):
-        self.ser = serial.Serial(port, 115200, timeout=1)
-
-    def readFromDevice(self, expectedLines=1):
-        lines = []
-        # Attempt to read expected lines; if device is slow, you may need retries
-        while len(lines) < expectedLines:
-            if self.ser.in_waiting:
-                line = self.ser.readline().decode().strip()
-                if line:
-                    lines.append(line)
-            else:
-                time.sleep(0.01)
-        return lines
-
-    def getBeaconPositioningDistances(self):
-        """Reads the measured distances (A,E,D,B,F,C) from the device."""
-        self.writeToDevice("bpm")
-        buffer = self.readFromDevice(1)[0]
-        values = list(map(float, buffer.split(" ")))
-        return values
-
-    def getRangingDistances(self):
-        """Reads the distances from the tags to the anchors."""
-        self.writeToDevice("rng")
-        lines = self.readFromDevice(2)
-        print(lines)
-        distances = []
-        # First line: Tag 1 distances
-        distances.append(list(map(float, lines[0][1:].split(" "))))
-        # Second line: Tag 2 distances or "0"
-        if lines[1] != "1":
-            distances.append(list(map(float, lines[1][1:].split(" "))))
-        else:
-            distances.append(None)
-        return distances
-
-    def writeToDevice(self, value):
-        self.ser.write((value + "\n").encode())
-
-    def __del__(self):
-        print("Closing port")
-        self.ser.close()
-
-
-class AnchorTagCLI:
-    def __init__(self, port="/dev/tty.usbmodem14101", testing=False):
-        self.testing = testing
-        self.serial_buffer = SerialBuffer(port)
-
-        # Distances between anchors (A,E,D,B,F,C)
-        # Corresponding to the measured_distances in original code.
-        self.measured_distances = [0.0]*6
-
-        # Distances from Tag 1 to anchors: A1, A2, A3, A4
-        self.tag_distances = {"A1": 0.0, "A2": 0.0, "A3": 0.0, "A4": 0.0}
-
-        # Distances from Tag 2 to anchors: A1, A2, A3, A4
-        self.tag2_distances = {"A1": 0.0, "A2": 0.0, "A3": 0.0, "A4": 0.0}
-
-        self.anchors = {}
-        self.anchors_coords_known = False
-
-        if self.testing:
-            # Set predefined test distances
-            for i, dist in enumerate(TEST_MEASURED_DISTANCES):
-                self.measured_distances[i] = dist
-
-            for (anchor, dist) in zip(self.tag_distances.keys(), TEST_TAG1_DISTANCES):
-                self.tag_distances[anchor] = dist
-
-            for (anchor, dist) in zip(self.tag2_distances.keys(), TEST_TAG2_DISTANCES):
-                self.tag2_distances[anchor] = dist
-
-    def determine_anchor_coords(self):
-        try:
-            measured_distances = np.array(self.measured_distances)
-            noise_level = 0.0
-            measured_distances_noisy = measured_distances + np.random.uniform(-noise_level, noise_level, size=len(measured_distances))
-
-            # Variables: x_B, y_B, x_C, y_C, y_A
-            initial_guess = [120, 100, 150, 200, 50] # [x_B, y_B, x_C, y_C, y_A]
-            maxBounds = 30000
-            bounds = ([0, 0, 0, 0, 0], [maxBounds] * 5)
-
-            def error_function(variables, measured):
-                x_B, y_B, x_C, y_C, y_A = variables
-                # measured: [A, E, D, B, F, C]
-                a_measured = measured[0]
-                e_measured = measured[1]
-                d_measured = measured[2]
-                b_measured = measured[3]
-                f_measured = measured[4]
-                c_measured = measured[5]
-
-                # A=(0,y_A), B=(x_B,y_B), C=(x_C,y_C), D=(0,0)
-                a_calc = np.sqrt((x_B - 0)**2 + (y_B - y_A)**2)  # A-B
-                b_calc = np.sqrt((x_C - x_B)**2 + (y_C - y_B)**2) # B-C
-                c_calc = np.sqrt(x_C**2 + y_C**2)                 # C-D
-                d_calc = y_A                                      # A-D
-                e_calc = np.sqrt(x_C**2 + (y_C - y_A)**2)         # A-C
-                f_calc = np.sqrt(x_B**2 + y_B**2)                 # B-D
-
-                return [
-                    a_calc - a_measured,
-                    b_calc - b_measured,
-                    c_calc - c_measured,
-                    d_calc - d_measured,
-                    e_calc - e_measured,
-                    f_calc - f_measured
-                ]
-
-            # Run least squares optimization
-            result_noisy = least_squares(
-                error_function,
-                initial_guess,
-                args=(measured_distances_noisy,),
-                bounds=bounds,
-                loss='soft_l1'
-            )
-            optimized_coords_noisy = result_noisy.x
-
-            self.anchors = {
-                "A1": (0, optimized_coords_noisy[4]),
-                "A2": (optimized_coords_noisy[0], optimized_coords_noisy[1]),
-                "A3": (optimized_coords_noisy[2], optimized_coords_noisy[3]),
-                "A4": (0, 0),
-            }
-            return {k: (round(v[0], 2), round(v[1], 2)) for k, v in self.anchors.items()}
-        except Exception as e:
-            print(f"Error generating anchors: {e}")
-
-    def calculate_tag_coordinates(self, tag_distances):
-        if not self.anchors_coords_known or len(self.anchors) < 3:
-            return None, None
-     
-        available_beacons = []
-        available_distances = []
-        for key in tag_distances.keys():
-            d = max(float(tag_distances[key]), 0)
-            available_distances.append(d)
-            available_beacons.append(self.anchors[key])
-
-        if len(available_beacons) < 3:
-            return None, None
-
-        def error_function(vars):
-            x, y = vars
-            residuals = []
-            for (bx, by), d_measured in zip(available_beacons, available_distances):
-                d_computed = np.sqrt((x - bx)**2 + (y - by)**2)
-                residuals.append(d_computed - d_measured)
-            return residuals
-
-        beacon_xs = [b[0] for b in available_beacons]
-        beacon_ys = [b[1] for b in available_beacons]
-        initial_guess = [np.mean(beacon_xs), np.mean(beacon_ys)]
-
-        x_min = min(beacon_xs) - 100
-        x_max = max(beacon_xs) + 100
-        y_min = min(beacon_ys) - 100
-        y_max = max(beacon_ys) + 100
-        bounds = ([x_min, y_min], [x_max, y_max])
-
-        result = least_squares(error_function, initial_guess, bounds=bounds, loss='soft_l1')
-        x_tag, y_tag = result.x
-        return x_tag, y_tag
-
-    def call_bpm(self):
-        if self.testing:
-            beacon_distances = TEST_MEASURED_DISTANCES
-        else:
-            beacon_distances = self.serial_buffer.getBeaconPositioningDistances()
-
-        for i, distance in enumerate(beacon_distances):
-            if i < len(self.measured_distances):
-                self.measured_distances[i] = distance
-
-        determined_anchor_coords = self.determine_anchor_coords()
-        if determined_anchor_coords:
-            self.anchors_coords_known = True
-            print("Anchor coordinates determined:")
-            for anchor, coords in determined_anchor_coords.items():
-                print(f"{anchor}: {coords}")
-
-    def update_distances_and_calculate_tags(self):
-        if not self.anchors_coords_known:
-            return
-
-        if self.testing:
-            ranging_distances = [TEST_TAG1_DISTANCES, TEST_TAG2_DISTANCES]
-        else:
-            ranging_distances = self.serial_buffer.getRangingDistances()
-
-        # Update tag 1 distances
-        if ranging_distances[0] is not None:
-            for i, distance in enumerate(ranging_distances[0]):
-                anchor = list(self.tag_distances.keys())[i]
-                self.tag_distances[anchor] = distance
-
-        # Update tag 2 distances
-        if ranging_distances[1] is not None:
-            for i, distance in enumerate(ranging_distances[1]):
-                anchor = list(self.tag2_distances.keys())[i]
-                self.tag2_distances[anchor] = distance
-
-        # Now calculate both tags
-        tag1_x, tag1_y = self.calculate_tag_coordinates(self.tag_distances)
-        valid_tag2_distances = [dist for dist in self.tag2_distances.values() if dist > 0]
-
-        # Check if there are enough valid distances for Tag 2
-        if len(valid_tag2_distances) < 3:
-            print(f"Insufficient valid distances for Tag 2: {len(valid_tag2_distances)} provided.")
-            tag2_x, tag2_y = None, None
-        else:
-            tag2_x, tag2_y = self.calculate_tag_coordinates(self.tag2_distances)
-
-        print("Tag Positions:")
-        if tag1_x is not None and tag1_y is not None:
-            print(f"Tag 1: ({tag1_x:.2f}, {tag1_y:.2f})")
-        else:
-            print("Tag 1: Not enough data")
-
-        if tag2_x is not None and tag2_y is not None:
-            print(f"Tag 2: ({tag2_x:.2f}, {tag2_y:.2f})")
-        else:
-            print("Tag 2: Not enough data")
-
-      
-        if tag1_x is not None and tag1_y is not None and tag2_x is not None and tag2_y is not None:
-            dx = tag2_x - tag1_x
-            dy = tag2_y - tag1_y
-            displacement = np.sqrt(dx**2 + dy**2)
-            angle_deg = np.degrees(np.arctan2(dy, dx))
-            if angle_deg < 0:
-                angle_deg += 360
-            print(f"Direction from Tag1 to Tag2: dx={dx:.2f}, dy={dy:.2f}, displacement={displacement:.2f}, angle={angle_deg:.2f}°")
-        return tag1_x, tag1_y
-
-if __name__ == "__main__":
-    app = AnchorTagCLI(port="/dev/tty.usbmodem14101", testing=False)
-    while True:
-        user_input = input("Enter command ('bpm' to set anchors, or 'quit' to exit): ").strip().lower()
-        if user_input == "bpm":
-            app.call_bpm()
-            print("Switching to continuous ranging updates (simulating 'rng' messages)...")
-            while True:
-                app.update_distances_and_calculate_tags()
-                time.sleep(1)
-        elif user_input == "quit":
-            print("Exiting program.")
-            break
\ No newline at end of file
diff --git a/ros2/src/build/robobin/build/lib/robobin/imu_node.py b/ros2/src/build/robobin/build/lib/robobin/imu_node.py
deleted file mode 100644
index d20c2dad0c8ab6525395a00d74ce5833f1fa2d94..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/build/lib/robobin/imu_node.py
+++ /dev/null
@@ -1,95 +0,0 @@
-#!/usr/bin/env python3
-
-import rclpy
-from rclpy.node import Node
-from sensor_msgs.msg import Imu
-from smbus2 import SMBus
-import time
-import math
-
-class BNO055Publisher(Node):
-    def __init__(self):
-        super().__init__('imu_node')
-        self.publisher_ = self.create_publisher(Imu, 'imu', 10)
-        self.timer = self.create_timer(0.1, self.timer_callback)
-        self.bus = SMBus(1)
-        self.address = 0x28
-        self.init_bno055()
-        time.sleep(1)
-
-    def write_register(self, register, value):
-        self.bus.write_byte_data(self.address, register, value)
-
-    def read_register(self, register, length=1):
-        if length == 1:
-            return self.bus.read_byte_data(self.address, register)
-        else:
-            return self.bus.read_i2c_block_data(self.address, register, length)
-
-    def init_bno055(self):
-        # Switch to CONFIG mode
-        self.write_register(0x3D, 0x00)
-        time.sleep(0.05)
-        # Set power mode to Normal
-        self.write_register(0x3E, 0x00)
-        # Set to NDOF mode
-        self.write_register(0x3D, 0x0C)
-        time.sleep(0.5)
-
-    def read_euler_angles(self):
-        data = self.read_register(0x1A, 6)
-        yaw = (data[1] << 8) | data[0]
-        roll = (data[3] << 8) | data[2]
-        pitch = (data[5] << 8) | data[4]
-        yaw = yaw if yaw < 32768 else yaw - 65536
-        roll = roll if roll < 32768 else roll - 65536
-        pitch = pitch if pitch < 32768 else pitch - 65536
-        yaw = yaw / 16.0
-        roll = roll / 16.0
-        pitch = pitch / 16.0
-        return yaw, pitch, roll
-
-    def timer_callback(self):
-        yaw, pitch, roll = self.read_euler_angles()
-        imu_msg = Imu()
-        imu_msg.header.stamp = self.get_clock().now().to_msg()
-        imu_msg.header.frame_id = 'imu_link'
-        # Convert degrees to radians
-        yaw_rad = -(math.radians(yaw))
-        roll_rad = -(math.radians(pitch))
-        pitch_rad = -(math.radians(roll))
-        # Compute quaternion
-        cy = math.cos(yaw_rad * 0.5)
-        sy = math.sin(yaw_rad * 0.5)
-        cp = math.cos(pitch_rad * 0.5)
-        sp = math.sin(pitch_rad * 0.5)
-        cr = math.cos(roll_rad * 0.5)
-        sr = math.sin(roll_rad * 0.5)
-        imu_msg.orientation.w = cr * cp * cy + sr * sp * sy
-        imu_msg.orientation.x = sr * cp * cy - cr * sp * sy
-        imu_msg.orientation.y = cr * sp * cy + sr * cp * sy
-        imu_msg.orientation.z = cr * cp * sy - sr * sp * cy
-
-        imu_msg.orientation_covariance = [0.0025, 0, 0,
-                                  0, 0.0025, 0,
-                                  0, 0, 0.0025]
-        imu_msg.angular_velocity_covariance = [0.02, 0, 0,
-                                            0, 0.02, 0,
-                                            0, 0, 0.02]
-        imu_msg.linear_acceleration_covariance = [0.04, 0, 0,
-                                                0, 0.04, 0,
-                                                0, 0, 0.04]
-
-
-        self.publisher_.publish(imu_msg)
-        #self.get_logger().info(f'Publishing: Yaw={yaw:.2f}, Pitch={pitch:.2f}, Roll={roll:.2f}')
-
-def main(args=None):
-    rclpy.init(args=args)
-    bno055_publisher = BNO055Publisher()
-    rclpy.spin(bno055_publisher)
-    bno055_publisher.destroy_node()
-    rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
\ No newline at end of file
diff --git a/ros2/src/build/robobin/build/lib/robobin/motor_control_node.py b/ros2/src/build/robobin/build/lib/robobin/motor_control_node.py
deleted file mode 100644
index 25786c4a14305145926601ce96e723029b42c750..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/build/lib/robobin/motor_control_node.py
+++ /dev/null
@@ -1,73 +0,0 @@
-#!/usr/bin/env python3
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Twist
-from gpiozero import PWMOutputDevice
-from time import sleep
-
-class Motor:
-    def __init__(self, node, EnaA, In1A, In2A, EnaB, In1B, In2B):
-        self.node = node
-        self.pwmA = PWMOutputDevice(EnaA)
-        self.in1A = PWMOutputDevice(In1A)
-        self.in2A = PWMOutputDevice(In2A)
-        self.pwmB = PWMOutputDevice(EnaB)
-        self.in1B = PWMOutputDevice(In1B)
-        self.in2B = PWMOutputDevice(In2B)
-
-    def move(self, speed=0.0, turn=0.0):
-        speed = max(-1, min(1, speed))
-        turn = max(-1, min(1, turn))
-
-        leftSpeed = speed - turn
-        rightSpeed = speed + turn
-        '''
-        left_speed = self.desired_speed - (turn_rate * self.motor.wheel_base / 2)
-        right_speed = self.desired_speed + (turn_rate * self.motor.wheel_base / 2)
-        '''
-
-        leftSpeed = max(-1, min(1, leftSpeed))
-        rightSpeed = max(-1, min(1, rightSpeed))
-
-        self.pwmA.value = abs(leftSpeed)
-        self.in1A.value = leftSpeed <=  0
-        self.in2A.value = leftSpeed > 0
-
-        self.pwmB.value = abs(rightSpeed)
-        self.in1B.value = rightSpeed > 0
-        self.in2B.value = rightSpeed <= 0
-
-        self.node.get_logger().info(f"Left Motor: Speed={leftSpeed}, Right Motor: Speed={rightSpeed}")
-
-
-    def stop(self):
-        self.pwmA.value = 0
-        self.pwmB.value = 0
-
-class MotorControlNode(Node):
-    def __init__(self):
-        super().__init__('motor_control_node')
-        self.get_logger().info("hello")
-        self.motor = Motor(self, 14, 15, 18, 17, 22, 27)
-        self.subscription = self.create_subscription(
-            Twist,
-            'cmd_vel',
-            self.cmd_vel_callback,
-            10
-        )
-
-    def cmd_vel_callback(self, msg):
-        linear_x = msg.linear.x
-        angular_z = msg.angular.z
-        self.motor.move(speed=linear_x, turn=angular_z)
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = MotorControlNode()
-    rclpy.spin(node)
-    rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
-
-#colcon build --symlink-install
\ No newline at end of file
diff --git a/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py b/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py
deleted file mode 100644
index 64c4d16fdc9953aae6337abffe5aa4ee71bc24dc..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py
+++ /dev/null
@@ -1,316 +0,0 @@
-import json
-import os
-import time
-import numpy as np
-from scipy.optimize import least_squares
-from geometry_msgs.msg import Point
-import rclpy
-from rclpy.node import Node
-from std_msgs.msg import String
-from sensor_msgs.msg import Imu
-import tf_transformations
-
-class SerialBuffer:
-    def __init__(self, port):
-        import serial
-        self.ser = serial.Serial(port, 115200, timeout=1)
-
-    def readFromDevice(self, expectedLines=1):
-        lines = []
-        while len(lines) < expectedLines:
-            if self.ser.in_waiting:
-                line = self.ser.readline().decode().strip()
-                if line:
-                    lines.append(line)
-            else:
-                time.sleep(0.01)
-        return lines
-
-    def getBeaconPositioningDistances(self):
-        # return [302, 463, 286, 304, 418, 328]
-        self.writeToDevice("bpm")
-        buffer = self.readFromDevice(1)[0]
-        values = list(map(float, buffer.split(" ")))
-        
-        return values
-
-    def getRangingDistances(self):
-        
-        self.writeToDevice("rng")
-        lines = self.readFromDevice(2)
-
-        print(lines)
-        distances = []
-        distances.append(list(map(float, lines[0][1:].split(" "))))
-        if lines[1] != "1":
-           distances.append(list(map(float, lines[1][1:].split(" "))))
-        else:
-            distances.append(None)
-        return distances
-
-    def writeToDevice(self, value):
-        self.ser.write((value + "\n").encode())
-
-    def __del__(self):
-        self.ser.close()
-
-class UWBNode(Node):
-    def __init__(self):
-        super().__init__('uwb_navigation_node')
-
-        self.publisher = self.create_publisher(Point, '/tag1_location', 10)
-        self.subscription = self.create_subscription(String, '/nav_command', self.handle_nav_command, 10)
-        self.imu_subscription = self.create_subscription(Imu, '/imu', self.handle_imu, 10)
-
-        self.current_yaw = None  # Store the current IMU yaw
-        self.uwb_to_imu_offset = None  # Offset between UWB and IMU heading
-        
-        self.serial_buffer = SerialBuffer("/dev/ttyACM0")
-        self.anchors = {}
-        self.anchors_coords_known = False
-        self.previous_tag1_position = None
-        anchors_file_path = os.path.join("src", "robobin", "robobin", "graphs", "anchors.json")
-        if os.path.exists(anchors_file_path):
-            try:
-                with open(anchors_file_path, 'r') as f:
-                    anchors_data = json.load(f)
-                    self.anchors = anchors_data
-                    self.anchors_coords_known = True
-                    self.get_logger().info("Anchor coordinates loaded from anchors.json.")
-            except Exception as e:
-                self.get_logger().error(f"Failed to load anchors.json: {e}")
-                self.anchors_coords_known = False
-        else:
-            self.get_logger().warning("anchors.json not found, anchor coordinates not known.")
-            self.anchors_coords_known = False
-
-        # Timer to continuously fetch and publish positions
-        self.timer = self.create_timer(1.0, self.update_positions)
-
-    def call_bpm(self):
-        try:
-            beacon_distances = self.serial_buffer.getBeaconPositioningDistances()
-            self.get_logger().info(f"Retreived values {beacon_distances }")
-            self.determine_anchor_coords(beacon_distances)
-            self.anchors_coords_known = True
-            self.get_logger().info("Anchor coordinates determined.")
-            anchors_file_path = os.path.join("src", "robobin", "robobin", "graphs", "anchors.json")
-            try:
-                with open(anchors_file_path, 'w') as f:
-                    json.dump(self.anchors, f)
-                self.get_logger().info("Anchor coordinates saved to anchors.json.")
-
-
-                graph = {
-                    "name": "Lab 1 Extended",
-                    "nodes": [],
-                    "connections": []
-                }
-
-                # Populate nodes with anchor data
-                anchor_names = ["A1", "A2", "A3", "A4"]
-                for i, (key, coords) in enumerate(self.anchors.items()):
-                    graph["nodes"].append({"name": anchor_names[i], "x": coords[0], "y": coords[1]})
-
-                # Create a fully connected adjacency matrix (all nodes connected)
-                num_nodes = len(graph["nodes"])
-                graph["connections"] = [[True if i != j else False for j in range(num_nodes)] for i in range(num_nodes)]
-
-                # Save graph to file
-                graph_file_path = os.path.join("src", "robobin", "robobin", "graphs", "graph.json")
-                with open(graph_file_path, 'w') as f:
-                    json.dump(graph, f, indent=2)
-                self.get_logger().info("Graph saved to graph.json.")
-
-       
-            except Exception as e:
-                self.get_logger().error(f"Failed to save anchors.json: {e}")
-
-        except Exception as e:
-            self.get_logger().error(f"Failed to determine anchors: {e}")
-
-    def handle_imu(self, msg):
-        # Extract yaw from quaternion
-        orientation_q = msg.orientation
-        orientation_list = [orientation_q.x, orientation_q.y, orientation_q.z, orientation_q.w]
-        _, _, yaw = tf_transformations.euler_from_quaternion(orientation_list)
-        
-        self.current_yaw = yaw  # Update current yaw
-        self.get_logger().info(f"IMU Yaw: {yaw:.2f} radians")
-    def determine_anchor_coords(self, measured_distances):
-        measured_distances = np.array(measured_distances)
-
-        initial_guess = [120, 100, 150, 200, 50]
-        bounds = ([0, 0, 0, 0, 0], [1000, 1000, 1000, 1000, 1000])
-
-        def error_function(variables, measured):
-            x_B, y_B, x_C, y_C, y_A = variables
-            a_calc = np.sqrt((x_B - 0)**2 + (y_B - y_A)**2)  # A-B
-            b_calc = np.sqrt((x_C - x_B)**2 + (y_C - y_B)**2)  # B-C
-            c_calc = np.sqrt(x_C**2 + y_C**2)  # C-D
-            d_calc = y_A  # A-D
-            e_calc = np.sqrt(x_C**2 + (y_C - y_A)**2)  # A-C
-            f_calc = np.sqrt(x_B**2 + y_B**2)  # B-D
-
-            return [
-                a_calc - measured[0],
-                b_calc - measured[3],
-                c_calc - measured[5],
-                d_calc - measured[2],
-                e_calc - measured[1],
-                f_calc - measured[4]
-            ]
-
-        result = least_squares(
-            error_function,
-            initial_guess,
-            args=(measured_distances,),
-            bounds=bounds,
-            loss='soft_l1'
-        )
-        x_B, y_B, x_C, y_C, y_A = result.x
-        self.anchors = {
-            "A1": (0, y_A),
-            "A2": (x_B, y_B),
-            "A3": (x_C, y_C),
-            "A4": (0, 0)
-        }
-
-    def calculate_tag_coordinates(self, tag_distances):
-        # self.get_logger().info(f"Tag distances: {tag_distances}")
-        if not self.anchors_coords_known or len(self.anchors) < 3:
-            self.get_logger().warning("Anchor coordinates not known.")
-            return None
-        
-        available_beacons = []
-        available_distances = []
-
-        for key, dist in tag_distances.items():
-            if dist > 0:
-                available_distances.append(dist)
-                available_beacons.append(self.anchors[key])
-
-        if len(available_beacons) < 3:
-            return None
-
-        def error_function(vars):
-            x, y = vars
-            residuals = []
-            for (bx, by), d_measured in zip(available_beacons, available_distances):
-                d_computed = np.sqrt((x - bx)**2 + (y - by)**2)
-                residuals.append(d_computed - d_measured)
-            return residuals
-
-        beacon_xs = [b[0] for b in available_beacons]
-        beacon_ys = [b[1] for b in available_beacons]
-        initial_guess = [np.mean(beacon_xs), np.mean(beacon_ys)]
-
-        bounds = (
-            [min(beacon_xs) - 100, min(beacon_ys) - 100],
-            [max(beacon_xs) + 100, max(beacon_ys) + 100]
-        )
-
-        result = least_squares(error_function, initial_guess, bounds=bounds, loss='soft_l1')
-        self.get_logger().info(f"Optimization result: {result.x}")
-        return tuple(result.x)
-
-    def update_positions(self):
-        self.get_logger().info("Updating positions...")
-        #self.get_logger().info(f"Is anchor coords known: {self.anchors_coords_known}")
-        if self.anchors_coords_known:
-            
-            
-
-            try:
-                ranging_distances = self.serial_buffer.getRangingDistances()
-                self.get_logger().info(f"Ranging Distances {ranging_distances}")
-                tag1_distances = ranging_distances[0]
-                self.get_logger().info(f"Tag1 distances {tag1_distances}")
-                tag_distances_dict = {
-                    "A1": tag1_distances[0],
-                    "A2": tag1_distances[1],
-                    "A3": tag1_distances[2],
-                    "A4": tag1_distances[3]
-                }
-                self.get_logger().info(f"Tag distances: {tag_distances_dict}")
-                tag1_position = self.calculate_tag_coordinates(tag_distances_dict)
-
-                if tag1_position is not None :
-                    self.previous_tag1_position = tag1_position
-                    position_msg = Point(x=tag1_position[0], y=tag1_position[1], z=0.0)
-                    self.publisher.publish(position_msg)
-                    #self.get_logger().info(f"Published new Tag 1 position: {tag1_position}")
-
-                #self.get_logger().info(f"Tag 1 position: {tag1_position}")
-                tag2_distances = ranging_distances[1]
-                self.get_logger().info(f"Tag2 distances {tag2_distances}")
-                tag2_position = None
-                if tag2_distances is not None:
-                    
-                    tag2_distances_dict = {
-                        "A1": tag2_distances[0],
-                        "A2": tag2_distances[1],
-                        "A3": tag2_distances[2],
-                        "A4": tag2_distances[3]
-                    }
-                    tag2_position = self.calculate_tag_coordinates(tag2_distances_dict)
-                else:
-                    self.get_logger().warning("Tag 2 is not known")
-      
-
-                # Calculate angle between tag1 and tag2, then print out the angle. @TODO: Move the bin forward to see which direction we are facing, then match the angle with the IMU yaw. This will then mean we can calculate the offset between the UWB and IMU heading.
-                if tag2_position is not None:
-                    displacement_x = tag2_position[0] - tag1_position[0]
-                    displacement_y = tag2_position[1] - tag1_position[1]
-                    
-                    # Calculate angle and distance
-                    displacement_angle = np.arctan2(displacement_y, displacement_x)  
-                    displacement_distance = np.sqrt(displacement_x**2 + displacement_y**2)
-                    
-                    self.get_logger().info(f"Displacement: dx={displacement_x:.2f}, dy={displacement_y:.2f}")
-                    self.get_logger().info(f"Displacement Angle: {np.degrees(displacement_angle):.2f}°")
-                    self.get_logger().info(f"Displacement Distance: {displacement_distance:.2f} units")
-                
-
-            except Exception as e:
-                self.get_logger().error(f"Error updating positions: {e}")
-    def clear_graph(self):
-        self.anchors_coords_known = False
-        self.anchors = {}
-        self.previous_tag1_position = None
-        graph_file_path = os.path.join("src", "robobin", "robobin", "graphs", "graph.json")
-        default_file_path = os.path.join("src", "robobin", "robobin", "graphs", "default_graph.json")
-        try:
-            with open(default_file_path, 'r') as f:
-                graph_data = json.load(f)
-                with open(graph_file_path, 'w') as f:
-                    json.dump(graph_data, f)
-        except FileNotFoundError:
-            self.get_logger().error(f"Error: File not found at {default_file_path}")
-        except json.JSONDecodeError as e:
-            self.get_logger().error(f"Error: Failed to decode JSON - {str(e)}")
-        except Exception as e:
-            self.get_logger().error(f"Error: {str(e)}")
-
-        self.get_logger().info("Graph cleared.")
-
-
-    def handle_nav_command(self, msg):
-        if msg.data == "BPM":
-            self.clear_graph()
-            self.call_bpm()
-            self.anchors_coords_known = True
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = UWBNode()
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == "__main__":
-    main()
diff --git a/ros2/src/build/robobin/build/lib/robobin/uwb_pathing_node.py b/ros2/src/build/robobin/build/lib/robobin/uwb_pathing_node.py
deleted file mode 100644
index dec8b95597d81d37e8cc8f3d74aef15b9c7702c8..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/build/lib/robobin/uwb_pathing_node.py
+++ /dev/null
@@ -1,122 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Twist, Point
-from math import sqrt, pow, atan2, radians, sin, cos
-import time
-
-
-class UWBPathingNode(Node):
-    def __init__(self):
-        super().__init__('uwb_pathing_node')
-
-        # Publisher for cmd_vel
-        self.cmd_vel_pub = self.create_publisher(Twist, '/cmd_vel', 10)
-
-        # Subscriptions
-        self.create_subscription(Point, '/start_location', self.current_location_callback, 10)
-        self.create_subscription(Point, '/target_location', self.target_location_callback, 10)
-
-        # Current and target positions
-        self.current_x = None
-        self.current_y = None
-        self.target_x = None
-        self.target_y = None
-
-        # Navigation thresholds
-        self.distance_threshold = 0.25  # meters
-        self.angle_threshold = radians(0.5)  # radians
-
-        self.kp_linear = 0.5  # Proportional gain for linear movement
-        self.kp_angular = 1.0  # Proportional gain for angular movement
-
-        self.get_logger().info('UWB Pathing Node started and waiting for positions.')
-
-    def current_location_callback(self, msg: Point):
-        """Callback to update the robot's current position."""
-        self.current_x = msg.x
-        self.current_y = msg.y
-        self.get_logger().info(f"Current Location Updated: x={self.current_x:.2f}, y={self.current_y:.2f}")
-        self.check_and_navigate()
-
-    def target_location_callback(self, msg: Point):
-        """Callback to update the target position."""
-        self.target_x = msg.x
-        self.target_y = msg.y
-        self.get_logger().info(f"Target Location Updated: x={self.target_x:.2f}, y={self.target_y:.2f}")
-        self.check_and_navigate()
-
-    def check_and_navigate(self):
-        """Check if both positions are available and navigate to the target."""
-        if self.current_x is not None and self.current_y is not None and self.target_x is not None and self.target_y is not None:
-            self.get_logger().info("Navigating to target...")
-            self.navigate_to_target()
-        else:
-            self.get_logger().warning("Waiting for both current and target positions to be available...")
-
-    def navigate_to_target(self):
-        # Ensure positions are known
-        if self.current_x is None or self.current_y is None or self.target_x is None or self.target_y is None:
-            self.get_logger().warning("Positions not fully known yet.")
-            return
-
-        # Calculate distance and angle to the target
-        displacement_x = self.target_x - self.current_x
-        displacement_y = self.target_y - self.current_y
-        distance_to_target = sqrt(pow(displacement_x, 2) + pow(displacement_y, 2))
-        angle_to_target = atan2(displacement_y, displacement_x)
-
-
-        # Check if we are close enough to the target
-        if distance_to_target <= self.distance_threshold:
-            self.stop_robot()
-            self.get_logger().info("Target reached successfully.")
-            return
-
-        # Calculate yaw error (assuming robot orientation 0 = facing x-axis)
-        # If you don't have actual orientation, you might assume the robot always faces the target directly
-        yaw_error = angle_to_target
-        yaw_error = atan2(sin(yaw_error), cos(yaw_error))  # Normalize angle
-        self.get_logger().info(f"Current Position: x={self.current_x:.2f}, y={self.current_y:.2f}")
-        self.get_logger().info(f"Target Position: x={self.target_x:.2f}, y={self.target_y:.2f}")
-        self.get_logger().info(f"Distance to Target: distance_to_target={distance_to_target:.2f} meters")
-        self.get_logger().info(f"Angle to Target: angle_to_target={angle_to_target:.2f} radians")
-        twist = Twist()
-
-        # Decide on angular velocity first
-        if abs(yaw_error) > self.angle_threshold:
-            angular_speed = self.kp_angular * abs(yaw_error)
-            twist.angular.z = angular_speed if yaw_error > 0 else -angular_speed
-            self.get_logger().info(f"Correcting Heading: yaw_error={yaw_error:.2f} radians")
-        else:
-            # Move forward when aligned with the target
-            linear_speed = self.kp_linear * distance_to_target
-            twist.linear.x = min(0.2, linear_speed)  # Limit max speed
-            self.get_logger().info(f"Moving to Target: distance={distance_to_target:.2f} meters")
-
-        # # Publish movement command
-        # self.cmd_vel_pub.publish(twist)
-
-
-    def stop_robot(self):
-        """Stops the robot by publishing zero velocities."""
-        twist = Twist()
-        self.cmd_vel_pub.publish(twist)
-        time.sleep(0.5)
-        self.get_logger().info("Robot stopped.")
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = UWBPathingNode()
-
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/src/build/robobin/colcon_build.rc b/ros2/src/build/robobin/colcon_build.rc
deleted file mode 100644
index 573541ac9702dd3969c9bc859d2b91ec1f7e6e56..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/colcon_build.rc
+++ /dev/null
@@ -1 +0,0 @@
-0
diff --git a/ros2/src/build/robobin/colcon_command_prefix_setup_py.sh b/ros2/src/build/robobin/colcon_command_prefix_setup_py.sh
deleted file mode 100644
index f9867d51322a8ef47d4951080db6e3cfd048835e..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/colcon_command_prefix_setup_py.sh
+++ /dev/null
@@ -1 +0,0 @@
-# generated from colcon_core/shell/template/command_prefix.sh.em
diff --git a/ros2/src/build/robobin/colcon_command_prefix_setup_py.sh.env b/ros2/src/build/robobin/colcon_command_prefix_setup_py.sh.env
deleted file mode 100644
index fac85e398c655a9dde45aa20896af81bd914a4a8..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/colcon_command_prefix_setup_py.sh.env
+++ /dev/null
@@ -1,63 +0,0 @@
-AMENT_PREFIX_PATH=/home/robobin/robobin/ros2/src/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy
-CMAKE_PREFIX_PATH=/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor
-COLCON=1
-COLCON_PREFIX_PATH=/home/robobin/robobin/ros2/src/install:/home/robobin/Robobin_Project/ros2/robobin_main/install
-COLORTERM=truecolor
-DBUS_SESSION_BUS_ADDRESS=unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a
-DBUS_STARTER_ADDRESS=unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a
-DBUS_STARTER_BUS_TYPE=session
-DEBUGINFOD_URLS=https://debuginfod.ubuntu.com
-DESKTOP_SESSION=ubuntu
-DISPLAY=:0
-GDMSESSION=ubuntu
-GNOME_DESKTOP_SESSION_ID=this-is-deprecated
-GNOME_SETUP_DISPLAY=:1
-GNOME_SHELL_SESSION_MODE=ubuntu
-GNOME_TERMINAL_SCREEN=/org/gnome/Terminal/screen/92f2849b_1746_4562_850c_1b14829cbe47
-GNOME_TERMINAL_SERVICE=:1.102
-GSM_SKIP_SSH_AGENT_WORKAROUND=true
-GTK_MODULES=gail:atk-bridge
-GZ_CONFIG_PATH=/opt/ros/jazzy/opt/sdformat_vendor/share/gz
-HOME=/home/robobin
-IM_CONFIG_PHASE=1
-LANG=en_US.UTF-8
-LC_ALL=en_US.UTF-8
-LD_LIBRARY_PATH=/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib
-LESSCLOSE=/usr/bin/lesspipe %s %s
-LESSOPEN=| /usr/bin/lesspipe %s
-LOGNAME=robobin
-LS_COLORS=rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:
-MEMORY_PRESSURE_WATCH=/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/app.slice/app-gnome\x2dsession\x2dmanager.slice/gnome-session-manager@ubuntu.service/memory.pressure
-MEMORY_PRESSURE_WRITE=c29tZSAyMDAwMDAgMjAwMDAwMAA=
-OLDPWD=/home/robobin/robobin/ros2
-PATH=/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin
-PWD=/home/robobin/robobin/ros2/src/build/robobin
-PYTHONPATH=/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages
-QT_ACCESSIBILITY=1
-QT_IM_MODULE=ibus
-ROS_AUTOMATIC_DISCOVERY_RANGE=SUBNET
-ROS_DISTRO=jazzy
-ROS_DOMAIN_ID=3
-ROS_PYTHON_VERSION=3
-ROS_VERSION=2
-SESSION_MANAGER=local/robobin-desktop:@/tmp/.ICE-unix/1594,unix/robobin-desktop:/tmp/.ICE-unix/1594
-SHELL=/bin/bash
-SHLVL=1
-SSH_AUTH_SOCK=/run/user/1002/keyring/ssh
-SYSTEMD_EXEC_PID=1594
-TERM=xterm-256color
-USER=robobin
-USERNAME=robobin
-VTE_VERSION=7600
-WAYLAND_DISPLAY=wayland-0
-XAUTHORITY=/run/user/1002/.mutter-Xwaylandauth.XGQ7Y2
-XDG_CONFIG_DIRS=/etc/xdg/xdg-ubuntu:/etc/xdg
-XDG_CURRENT_DESKTOP=ubuntu:GNOME
-XDG_DATA_DIRS=/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop
-XDG_MENU_PREFIX=gnome-
-XDG_RUNTIME_DIR=/run/user/1002
-XDG_SESSION_CLASS=user
-XDG_SESSION_DESKTOP=ubuntu
-XDG_SESSION_TYPE=wayland
-XMODIFIERS=@im=ibus
-_=/usr/bin/colcon
diff --git a/ros2/src/build/robobin/install.log b/ros2/src/build/robobin/install.log
deleted file mode 100644
index 7b122f33d4965065ff45740f3cfffe3560a2a115..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/install.log
+++ /dev/null
@@ -1,27 +0,0 @@
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__init__.py
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/api_node.py
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/motor_control_node.cpython-312.pyc
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/__init__.cpython-312.pyc
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_navigation_node.cpython-312.pyc
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/api_node.cpython-312.pyc
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/message_handler.cpython-312.pyc
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/__init__.cpython-312.pyc
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/connection_manager.cpython-312.pyc
-/home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index/packages/robobin
-/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.xml
-/home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch/robobin_launch.py
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/SOURCES.txt
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/top_level.txt
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/PKG-INFO
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/zip-safe
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/requires.txt
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/dependency_links.txt
-/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/entry_points.txt
-/home/robobin/robobin/ros2/src/install/robobin/lib/robobin/api_node
-/home/robobin/robobin/ros2/src/install/robobin/lib/robobin/motor_control_node
-/home/robobin/robobin/ros2/src/install/robobin/lib/robobin/uwb_navigation_node
diff --git a/ros2/src/build/robobin/prefix_override/__pycache__/sitecustomize.cpython-312.pyc b/ros2/src/build/robobin/prefix_override/__pycache__/sitecustomize.cpython-312.pyc
deleted file mode 100644
index 00a14ffe9b623ab9954b5139271b1b28d30b3df7..0000000000000000000000000000000000000000
Binary files a/ros2/src/build/robobin/prefix_override/__pycache__/sitecustomize.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/build/robobin/prefix_override/sitecustomize.py b/ros2/src/build/robobin/prefix_override/sitecustomize.py
deleted file mode 100644
index 9da839acae63cbd121d9b9304479105f92722e18..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/prefix_override/sitecustomize.py
+++ /dev/null
@@ -1,4 +0,0 @@
-import sys
-if sys.prefix == '/usr':
-    sys.real_prefix = sys.prefix
-    sys.prefix = sys.exec_prefix = '/home/robobin/robobin/ros2/src/install/robobin'
diff --git a/ros2/src/build/robobin/robobin.egg-info/PKG-INFO b/ros2/src/build/robobin/robobin.egg-info/PKG-INFO
deleted file mode 100644
index 59b425a79a72e98ee9bcafffada085b85d328236..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/robobin.egg-info/PKG-INFO
+++ /dev/null
@@ -1,7 +0,0 @@
-Metadata-Version: 2.1
-Name: robobin
-Version: 0.0.0
-Summary: TODO: Package description
-Maintainer: paulw
-Maintainer-email: plw1g21@soton.ac.uk
-License: TODO: License declaration
diff --git a/ros2/src/build/robobin/robobin.egg-info/SOURCES.txt b/ros2/src/build/robobin/robobin.egg-info/SOURCES.txt
deleted file mode 100644
index 2fe204918a694fd60d88ab57b64a95b9b52c6acb..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/robobin.egg-info/SOURCES.txt
+++ /dev/null
@@ -1,22 +0,0 @@
-package.xml
-setup.cfg
-setup.py
-../build/robobin/robobin.egg-info/PKG-INFO
-../build/robobin/robobin.egg-info/SOURCES.txt
-../build/robobin/robobin.egg-info/dependency_links.txt
-../build/robobin/robobin.egg-info/entry_points.txt
-../build/robobin/robobin.egg-info/requires.txt
-../build/robobin/robobin.egg-info/top_level.txt
-../build/robobin/robobin.egg-info/zip-safe
-launch/robobin_launch.py
-resource/robobin
-robobin/__init__.py
-robobin/api_node.py
-robobin/motor_control_node.py
-robobin/uwb_navigation_node.py
-robobin/helpers/__init__.py
-robobin/helpers/connection_manager.py
-robobin/helpers/message_handler.py
-test/test_copyright.py
-test/test_flake8.py
-test/test_pep257.py
\ No newline at end of file
diff --git a/ros2/src/build/robobin/robobin.egg-info/dependency_links.txt b/ros2/src/build/robobin/robobin.egg-info/dependency_links.txt
deleted file mode 100644
index 8b137891791fe96927ad78e64b0aad7bded08bdc..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/robobin.egg-info/dependency_links.txt
+++ /dev/null
@@ -1 +0,0 @@
-
diff --git a/ros2/src/build/robobin/robobin.egg-info/entry_points.txt b/ros2/src/build/robobin/robobin.egg-info/entry_points.txt
deleted file mode 100644
index a569c6445838df1de986e4c1140c21af9733dc9c..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/robobin.egg-info/entry_points.txt
+++ /dev/null
@@ -1,4 +0,0 @@
-[console_scripts]
-api_node = robobin.api_node:main
-motor_control_node = robobin.motor_control_node:main
-uwb_navigation_node = robobin.uwb_navigation_node:main
diff --git a/ros2/src/build/robobin/robobin.egg-info/requires.txt b/ros2/src/build/robobin/robobin.egg-info/requires.txt
deleted file mode 100644
index 49fe098d9e6bccd89482b34510da60ab28556880..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/robobin.egg-info/requires.txt
+++ /dev/null
@@ -1 +0,0 @@
-setuptools
diff --git a/ros2/src/build/robobin/robobin.egg-info/top_level.txt b/ros2/src/build/robobin/robobin.egg-info/top_level.txt
deleted file mode 100644
index 2ca7c929754f574fe60649fed5f1333479af4ef7..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/robobin.egg-info/top_level.txt
+++ /dev/null
@@ -1 +0,0 @@
-robobin
diff --git a/ros2/src/build/robobin/robobin.egg-info/zip-safe b/ros2/src/build/robobin/robobin.egg-info/zip-safe
deleted file mode 100644
index 8b137891791fe96927ad78e64b0aad7bded08bdc..0000000000000000000000000000000000000000
--- a/ros2/src/build/robobin/robobin.egg-info/zip-safe
+++ /dev/null
@@ -1 +0,0 @@
-
diff --git a/ros2/src/install/.colcon_install_layout b/ros2/src/install/.colcon_install_layout
deleted file mode 100644
index 3aad5336af1f22b8088508218dceeda3d7bc8cc2..0000000000000000000000000000000000000000
--- a/ros2/src/install/.colcon_install_layout
+++ /dev/null
@@ -1 +0,0 @@
-isolated
diff --git a/ros2/src/install/COLCON_IGNORE b/ros2/src/install/COLCON_IGNORE
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/install/_local_setup_util_ps1.py b/ros2/src/install/_local_setup_util_ps1.py
deleted file mode 100644
index 3c6d9e8779050f742ec78af8a4d55abc4de7841b..0000000000000000000000000000000000000000
--- a/ros2/src/install/_local_setup_util_ps1.py
+++ /dev/null
@@ -1,407 +0,0 @@
-# Copyright 2016-2019 Dirk Thomas
-# Licensed under the Apache License, Version 2.0
-
-import argparse
-from collections import OrderedDict
-import os
-from pathlib import Path
-import sys
-
-
-FORMAT_STR_COMMENT_LINE = '# {comment}'
-FORMAT_STR_SET_ENV_VAR = 'Set-Item -Path "Env:{name}" -Value "{value}"'
-FORMAT_STR_USE_ENV_VAR = '$env:{name}'
-FORMAT_STR_INVOKE_SCRIPT = '_colcon_prefix_powershell_source_script "{script_path}"'  # noqa: E501
-FORMAT_STR_REMOVE_LEADING_SEPARATOR = ''  # noqa: E501
-FORMAT_STR_REMOVE_TRAILING_SEPARATOR = ''  # noqa: E501
-
-DSV_TYPE_APPEND_NON_DUPLICATE = 'append-non-duplicate'
-DSV_TYPE_PREPEND_NON_DUPLICATE = 'prepend-non-duplicate'
-DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS = 'prepend-non-duplicate-if-exists'
-DSV_TYPE_SET = 'set'
-DSV_TYPE_SET_IF_UNSET = 'set-if-unset'
-DSV_TYPE_SOURCE = 'source'
-
-
-def main(argv=sys.argv[1:]):  # noqa: D103
-    parser = argparse.ArgumentParser(
-        description='Output shell commands for the packages in topological '
-                    'order')
-    parser.add_argument(
-        'primary_extension',
-        help='The file extension of the primary shell')
-    parser.add_argument(
-        'additional_extension', nargs='?',
-        help='The additional file extension to be considered')
-    parser.add_argument(
-        '--merged-install', action='store_true',
-        help='All install prefixes are merged into a single location')
-    args = parser.parse_args(argv)
-
-    packages = get_packages(Path(__file__).parent, args.merged_install)
-
-    ordered_packages = order_packages(packages)
-    for pkg_name in ordered_packages:
-        if _include_comments():
-            print(
-                FORMAT_STR_COMMENT_LINE.format_map(
-                    {'comment': 'Package: ' + pkg_name}))
-        prefix = os.path.abspath(os.path.dirname(__file__))
-        if not args.merged_install:
-            prefix = os.path.join(prefix, pkg_name)
-        for line in get_commands(
-            pkg_name, prefix, args.primary_extension,
-            args.additional_extension
-        ):
-            print(line)
-
-    for line in _remove_ending_separators():
-        print(line)
-
-
-def get_packages(prefix_path, merged_install):
-    """
-    Find packages based on colcon-specific files created during installation.
-
-    :param Path prefix_path: The install prefix path of all packages
-    :param bool merged_install: The flag if the packages are all installed
-      directly in the prefix or if each package is installed in a subdirectory
-      named after the package
-    :returns: A mapping from the package name to the set of runtime
-      dependencies
-    :rtype: dict
-    """
-    packages = {}
-    # since importing colcon_core isn't feasible here the following constant
-    # must match colcon_core.location.get_relative_package_index_path()
-    subdirectory = 'share/colcon-core/packages'
-    if merged_install:
-        # return if workspace is empty
-        if not (prefix_path / subdirectory).is_dir():
-            return packages
-        # find all files in the subdirectory
-        for p in (prefix_path / subdirectory).iterdir():
-            if not p.is_file():
-                continue
-            if p.name.startswith('.'):
-                continue
-            add_package_runtime_dependencies(p, packages)
-    else:
-        # for each subdirectory look for the package specific file
-        for p in prefix_path.iterdir():
-            if not p.is_dir():
-                continue
-            if p.name.startswith('.'):
-                continue
-            p = p / subdirectory / p.name
-            if p.is_file():
-                add_package_runtime_dependencies(p, packages)
-
-    # remove unknown dependencies
-    pkg_names = set(packages.keys())
-    for k in packages.keys():
-        packages[k] = {d for d in packages[k] if d in pkg_names}
-
-    return packages
-
-
-def add_package_runtime_dependencies(path, packages):
-    """
-    Check the path and if it exists extract the packages runtime dependencies.
-
-    :param Path path: The resource file containing the runtime dependencies
-    :param dict packages: A mapping from package names to the sets of runtime
-      dependencies to add to
-    """
-    content = path.read_text()
-    dependencies = set(content.split(os.pathsep) if content else [])
-    packages[path.name] = dependencies
-
-
-def order_packages(packages):
-    """
-    Order packages topologically.
-
-    :param dict packages: A mapping from package name to the set of runtime
-      dependencies
-    :returns: The package names
-    :rtype: list
-    """
-    # select packages with no dependencies in alphabetical order
-    to_be_ordered = list(packages.keys())
-    ordered = []
-    while to_be_ordered:
-        pkg_names_without_deps = [
-            name for name in to_be_ordered if not packages[name]]
-        if not pkg_names_without_deps:
-            reduce_cycle_set(packages)
-            raise RuntimeError(
-                'Circular dependency between: ' + ', '.join(sorted(packages)))
-        pkg_names_without_deps.sort()
-        pkg_name = pkg_names_without_deps[0]
-        to_be_ordered.remove(pkg_name)
-        ordered.append(pkg_name)
-        # remove item from dependency lists
-        for k in list(packages.keys()):
-            if pkg_name in packages[k]:
-                packages[k].remove(pkg_name)
-    return ordered
-
-
-def reduce_cycle_set(packages):
-    """
-    Reduce the set of packages to the ones part of the circular dependency.
-
-    :param dict packages: A mapping from package name to the set of runtime
-      dependencies which is modified in place
-    """
-    last_depended = None
-    while len(packages) > 0:
-        # get all remaining dependencies
-        depended = set()
-        for pkg_name, dependencies in packages.items():
-            depended = depended.union(dependencies)
-        # remove all packages which are not dependent on
-        for name in list(packages.keys()):
-            if name not in depended:
-                del packages[name]
-        if last_depended:
-            # if remaining packages haven't changed return them
-            if last_depended == depended:
-                return packages.keys()
-        # otherwise reduce again
-        last_depended = depended
-
-
-def _include_comments():
-    # skipping comment lines when COLCON_TRACE is not set speeds up the
-    # processing especially on Windows
-    return bool(os.environ.get('COLCON_TRACE'))
-
-
-def get_commands(pkg_name, prefix, primary_extension, additional_extension):
-    commands = []
-    package_dsv_path = os.path.join(prefix, 'share', pkg_name, 'package.dsv')
-    if os.path.exists(package_dsv_path):
-        commands += process_dsv_file(
-            package_dsv_path, prefix, primary_extension, additional_extension)
-    return commands
-
-
-def process_dsv_file(
-    dsv_path, prefix, primary_extension=None, additional_extension=None
-):
-    commands = []
-    if _include_comments():
-        commands.append(FORMAT_STR_COMMENT_LINE.format_map({'comment': dsv_path}))
-    with open(dsv_path, 'r') as h:
-        content = h.read()
-    lines = content.splitlines()
-
-    basenames = OrderedDict()
-    for i, line in enumerate(lines):
-        # skip over empty or whitespace-only lines
-        if not line.strip():
-            continue
-        # skip over comments
-        if line.startswith('#'):
-            continue
-        try:
-            type_, remainder = line.split(';', 1)
-        except ValueError:
-            raise RuntimeError(
-                "Line %d in '%s' doesn't contain a semicolon separating the "
-                'type from the arguments' % (i + 1, dsv_path))
-        if type_ != DSV_TYPE_SOURCE:
-            # handle non-source lines
-            try:
-                commands += handle_dsv_types_except_source(
-                    type_, remainder, prefix)
-            except RuntimeError as e:
-                raise RuntimeError(
-                    "Line %d in '%s' %s" % (i + 1, dsv_path, e)) from e
-        else:
-            # group remaining source lines by basename
-            path_without_ext, ext = os.path.splitext(remainder)
-            if path_without_ext not in basenames:
-                basenames[path_without_ext] = set()
-            assert ext.startswith('.')
-            ext = ext[1:]
-            if ext in (primary_extension, additional_extension):
-                basenames[path_without_ext].add(ext)
-
-    # add the dsv extension to each basename if the file exists
-    for basename, extensions in basenames.items():
-        if not os.path.isabs(basename):
-            basename = os.path.join(prefix, basename)
-        if os.path.exists(basename + '.dsv'):
-            extensions.add('dsv')
-
-    for basename, extensions in basenames.items():
-        if not os.path.isabs(basename):
-            basename = os.path.join(prefix, basename)
-        if 'dsv' in extensions:
-            # process dsv files recursively
-            commands += process_dsv_file(
-                basename + '.dsv', prefix, primary_extension=primary_extension,
-                additional_extension=additional_extension)
-        elif primary_extension in extensions and len(extensions) == 1:
-            # source primary-only files
-            commands += [
-                FORMAT_STR_INVOKE_SCRIPT.format_map({
-                    'prefix': prefix,
-                    'script_path': basename + '.' + primary_extension})]
-        elif additional_extension in extensions:
-            # source non-primary files
-            commands += [
-                FORMAT_STR_INVOKE_SCRIPT.format_map({
-                    'prefix': prefix,
-                    'script_path': basename + '.' + additional_extension})]
-
-    return commands
-
-
-def handle_dsv_types_except_source(type_, remainder, prefix):
-    commands = []
-    if type_ in (DSV_TYPE_SET, DSV_TYPE_SET_IF_UNSET):
-        try:
-            env_name, value = remainder.split(';', 1)
-        except ValueError:
-            raise RuntimeError(
-                "doesn't contain a semicolon separating the environment name "
-                'from the value')
-        try_prefixed_value = os.path.join(prefix, value) if value else prefix
-        if os.path.exists(try_prefixed_value):
-            value = try_prefixed_value
-        if type_ == DSV_TYPE_SET:
-            commands += _set(env_name, value)
-        elif type_ == DSV_TYPE_SET_IF_UNSET:
-            commands += _set_if_unset(env_name, value)
-        else:
-            assert False
-    elif type_ in (
-        DSV_TYPE_APPEND_NON_DUPLICATE,
-        DSV_TYPE_PREPEND_NON_DUPLICATE,
-        DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS
-    ):
-        try:
-            env_name_and_values = remainder.split(';')
-        except ValueError:
-            raise RuntimeError(
-                "doesn't contain a semicolon separating the environment name "
-                'from the values')
-        env_name = env_name_and_values[0]
-        values = env_name_and_values[1:]
-        for value in values:
-            if not value:
-                value = prefix
-            elif not os.path.isabs(value):
-                value = os.path.join(prefix, value)
-            if (
-                type_ == DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS and
-                not os.path.exists(value)
-            ):
-                comment = f'skip extending {env_name} with not existing ' \
-                    f'path: {value}'
-                if _include_comments():
-                    commands.append(
-                        FORMAT_STR_COMMENT_LINE.format_map({'comment': comment}))
-            elif type_ == DSV_TYPE_APPEND_NON_DUPLICATE:
-                commands += _append_unique_value(env_name, value)
-            else:
-                commands += _prepend_unique_value(env_name, value)
-    else:
-        raise RuntimeError(
-            'contains an unknown environment hook type: ' + type_)
-    return commands
-
-
-env_state = {}
-
-
-def _append_unique_value(name, value):
-    global env_state
-    if name not in env_state:
-        if os.environ.get(name):
-            env_state[name] = set(os.environ[name].split(os.pathsep))
-        else:
-            env_state[name] = set()
-    # append even if the variable has not been set yet, in case a shell script sets the
-    # same variable without the knowledge of this Python script.
-    # later _remove_ending_separators() will cleanup any unintentional leading separator
-    extend = FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + os.pathsep
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': extend + value})
-    if value not in env_state[name]:
-        env_state[name].add(value)
-    else:
-        if not _include_comments():
-            return []
-        line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
-    return [line]
-
-
-def _prepend_unique_value(name, value):
-    global env_state
-    if name not in env_state:
-        if os.environ.get(name):
-            env_state[name] = set(os.environ[name].split(os.pathsep))
-        else:
-            env_state[name] = set()
-    # prepend even if the variable has not been set yet, in case a shell script sets the
-    # same variable without the knowledge of this Python script.
-    # later _remove_ending_separators() will cleanup any unintentional trailing separator
-    extend = os.pathsep + FORMAT_STR_USE_ENV_VAR.format_map({'name': name})
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': value + extend})
-    if value not in env_state[name]:
-        env_state[name].add(value)
-    else:
-        if not _include_comments():
-            return []
-        line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
-    return [line]
-
-
-# generate commands for removing prepended underscores
-def _remove_ending_separators():
-    # do nothing if the shell extension does not implement the logic
-    if FORMAT_STR_REMOVE_TRAILING_SEPARATOR is None:
-        return []
-
-    global env_state
-    commands = []
-    for name in env_state:
-        # skip variables that already had values before this script started prepending
-        if name in os.environ:
-            continue
-        commands += [
-            FORMAT_STR_REMOVE_LEADING_SEPARATOR.format_map({'name': name}),
-            FORMAT_STR_REMOVE_TRAILING_SEPARATOR.format_map({'name': name})]
-    return commands
-
-
-def _set(name, value):
-    global env_state
-    env_state[name] = value
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': value})
-    return [line]
-
-
-def _set_if_unset(name, value):
-    global env_state
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': value})
-    if env_state.get(name, os.environ.get(name)):
-        line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
-    return [line]
-
-
-if __name__ == '__main__':  # pragma: no cover
-    try:
-        rc = main()
-    except RuntimeError as e:
-        print(str(e), file=sys.stderr)
-        rc = 1
-    sys.exit(rc)
diff --git a/ros2/src/install/_local_setup_util_sh.py b/ros2/src/install/_local_setup_util_sh.py
deleted file mode 100644
index f67eaa9891ec587c4bbe364da6b18b5c65631f4d..0000000000000000000000000000000000000000
--- a/ros2/src/install/_local_setup_util_sh.py
+++ /dev/null
@@ -1,407 +0,0 @@
-# Copyright 2016-2019 Dirk Thomas
-# Licensed under the Apache License, Version 2.0
-
-import argparse
-from collections import OrderedDict
-import os
-from pathlib import Path
-import sys
-
-
-FORMAT_STR_COMMENT_LINE = '# {comment}'
-FORMAT_STR_SET_ENV_VAR = 'export {name}="{value}"'
-FORMAT_STR_USE_ENV_VAR = '${name}'
-FORMAT_STR_INVOKE_SCRIPT = 'COLCON_CURRENT_PREFIX="{prefix}" _colcon_prefix_sh_source_script "{script_path}"'  # noqa: E501
-FORMAT_STR_REMOVE_LEADING_SEPARATOR = 'if [ "$(echo -n ${name} | head -c 1)" = ":" ]; then export {name}=${{{name}#?}} ; fi'  # noqa: E501
-FORMAT_STR_REMOVE_TRAILING_SEPARATOR = 'if [ "$(echo -n ${name} | tail -c 1)" = ":" ]; then export {name}=${{{name}%?}} ; fi'  # noqa: E501
-
-DSV_TYPE_APPEND_NON_DUPLICATE = 'append-non-duplicate'
-DSV_TYPE_PREPEND_NON_DUPLICATE = 'prepend-non-duplicate'
-DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS = 'prepend-non-duplicate-if-exists'
-DSV_TYPE_SET = 'set'
-DSV_TYPE_SET_IF_UNSET = 'set-if-unset'
-DSV_TYPE_SOURCE = 'source'
-
-
-def main(argv=sys.argv[1:]):  # noqa: D103
-    parser = argparse.ArgumentParser(
-        description='Output shell commands for the packages in topological '
-                    'order')
-    parser.add_argument(
-        'primary_extension',
-        help='The file extension of the primary shell')
-    parser.add_argument(
-        'additional_extension', nargs='?',
-        help='The additional file extension to be considered')
-    parser.add_argument(
-        '--merged-install', action='store_true',
-        help='All install prefixes are merged into a single location')
-    args = parser.parse_args(argv)
-
-    packages = get_packages(Path(__file__).parent, args.merged_install)
-
-    ordered_packages = order_packages(packages)
-    for pkg_name in ordered_packages:
-        if _include_comments():
-            print(
-                FORMAT_STR_COMMENT_LINE.format_map(
-                    {'comment': 'Package: ' + pkg_name}))
-        prefix = os.path.abspath(os.path.dirname(__file__))
-        if not args.merged_install:
-            prefix = os.path.join(prefix, pkg_name)
-        for line in get_commands(
-            pkg_name, prefix, args.primary_extension,
-            args.additional_extension
-        ):
-            print(line)
-
-    for line in _remove_ending_separators():
-        print(line)
-
-
-def get_packages(prefix_path, merged_install):
-    """
-    Find packages based on colcon-specific files created during installation.
-
-    :param Path prefix_path: The install prefix path of all packages
-    :param bool merged_install: The flag if the packages are all installed
-      directly in the prefix or if each package is installed in a subdirectory
-      named after the package
-    :returns: A mapping from the package name to the set of runtime
-      dependencies
-    :rtype: dict
-    """
-    packages = {}
-    # since importing colcon_core isn't feasible here the following constant
-    # must match colcon_core.location.get_relative_package_index_path()
-    subdirectory = 'share/colcon-core/packages'
-    if merged_install:
-        # return if workspace is empty
-        if not (prefix_path / subdirectory).is_dir():
-            return packages
-        # find all files in the subdirectory
-        for p in (prefix_path / subdirectory).iterdir():
-            if not p.is_file():
-                continue
-            if p.name.startswith('.'):
-                continue
-            add_package_runtime_dependencies(p, packages)
-    else:
-        # for each subdirectory look for the package specific file
-        for p in prefix_path.iterdir():
-            if not p.is_dir():
-                continue
-            if p.name.startswith('.'):
-                continue
-            p = p / subdirectory / p.name
-            if p.is_file():
-                add_package_runtime_dependencies(p, packages)
-
-    # remove unknown dependencies
-    pkg_names = set(packages.keys())
-    for k in packages.keys():
-        packages[k] = {d for d in packages[k] if d in pkg_names}
-
-    return packages
-
-
-def add_package_runtime_dependencies(path, packages):
-    """
-    Check the path and if it exists extract the packages runtime dependencies.
-
-    :param Path path: The resource file containing the runtime dependencies
-    :param dict packages: A mapping from package names to the sets of runtime
-      dependencies to add to
-    """
-    content = path.read_text()
-    dependencies = set(content.split(os.pathsep) if content else [])
-    packages[path.name] = dependencies
-
-
-def order_packages(packages):
-    """
-    Order packages topologically.
-
-    :param dict packages: A mapping from package name to the set of runtime
-      dependencies
-    :returns: The package names
-    :rtype: list
-    """
-    # select packages with no dependencies in alphabetical order
-    to_be_ordered = list(packages.keys())
-    ordered = []
-    while to_be_ordered:
-        pkg_names_without_deps = [
-            name for name in to_be_ordered if not packages[name]]
-        if not pkg_names_without_deps:
-            reduce_cycle_set(packages)
-            raise RuntimeError(
-                'Circular dependency between: ' + ', '.join(sorted(packages)))
-        pkg_names_without_deps.sort()
-        pkg_name = pkg_names_without_deps[0]
-        to_be_ordered.remove(pkg_name)
-        ordered.append(pkg_name)
-        # remove item from dependency lists
-        for k in list(packages.keys()):
-            if pkg_name in packages[k]:
-                packages[k].remove(pkg_name)
-    return ordered
-
-
-def reduce_cycle_set(packages):
-    """
-    Reduce the set of packages to the ones part of the circular dependency.
-
-    :param dict packages: A mapping from package name to the set of runtime
-      dependencies which is modified in place
-    """
-    last_depended = None
-    while len(packages) > 0:
-        # get all remaining dependencies
-        depended = set()
-        for pkg_name, dependencies in packages.items():
-            depended = depended.union(dependencies)
-        # remove all packages which are not dependent on
-        for name in list(packages.keys()):
-            if name not in depended:
-                del packages[name]
-        if last_depended:
-            # if remaining packages haven't changed return them
-            if last_depended == depended:
-                return packages.keys()
-        # otherwise reduce again
-        last_depended = depended
-
-
-def _include_comments():
-    # skipping comment lines when COLCON_TRACE is not set speeds up the
-    # processing especially on Windows
-    return bool(os.environ.get('COLCON_TRACE'))
-
-
-def get_commands(pkg_name, prefix, primary_extension, additional_extension):
-    commands = []
-    package_dsv_path = os.path.join(prefix, 'share', pkg_name, 'package.dsv')
-    if os.path.exists(package_dsv_path):
-        commands += process_dsv_file(
-            package_dsv_path, prefix, primary_extension, additional_extension)
-    return commands
-
-
-def process_dsv_file(
-    dsv_path, prefix, primary_extension=None, additional_extension=None
-):
-    commands = []
-    if _include_comments():
-        commands.append(FORMAT_STR_COMMENT_LINE.format_map({'comment': dsv_path}))
-    with open(dsv_path, 'r') as h:
-        content = h.read()
-    lines = content.splitlines()
-
-    basenames = OrderedDict()
-    for i, line in enumerate(lines):
-        # skip over empty or whitespace-only lines
-        if not line.strip():
-            continue
-        # skip over comments
-        if line.startswith('#'):
-            continue
-        try:
-            type_, remainder = line.split(';', 1)
-        except ValueError:
-            raise RuntimeError(
-                "Line %d in '%s' doesn't contain a semicolon separating the "
-                'type from the arguments' % (i + 1, dsv_path))
-        if type_ != DSV_TYPE_SOURCE:
-            # handle non-source lines
-            try:
-                commands += handle_dsv_types_except_source(
-                    type_, remainder, prefix)
-            except RuntimeError as e:
-                raise RuntimeError(
-                    "Line %d in '%s' %s" % (i + 1, dsv_path, e)) from e
-        else:
-            # group remaining source lines by basename
-            path_without_ext, ext = os.path.splitext(remainder)
-            if path_without_ext not in basenames:
-                basenames[path_without_ext] = set()
-            assert ext.startswith('.')
-            ext = ext[1:]
-            if ext in (primary_extension, additional_extension):
-                basenames[path_without_ext].add(ext)
-
-    # add the dsv extension to each basename if the file exists
-    for basename, extensions in basenames.items():
-        if not os.path.isabs(basename):
-            basename = os.path.join(prefix, basename)
-        if os.path.exists(basename + '.dsv'):
-            extensions.add('dsv')
-
-    for basename, extensions in basenames.items():
-        if not os.path.isabs(basename):
-            basename = os.path.join(prefix, basename)
-        if 'dsv' in extensions:
-            # process dsv files recursively
-            commands += process_dsv_file(
-                basename + '.dsv', prefix, primary_extension=primary_extension,
-                additional_extension=additional_extension)
-        elif primary_extension in extensions and len(extensions) == 1:
-            # source primary-only files
-            commands += [
-                FORMAT_STR_INVOKE_SCRIPT.format_map({
-                    'prefix': prefix,
-                    'script_path': basename + '.' + primary_extension})]
-        elif additional_extension in extensions:
-            # source non-primary files
-            commands += [
-                FORMAT_STR_INVOKE_SCRIPT.format_map({
-                    'prefix': prefix,
-                    'script_path': basename + '.' + additional_extension})]
-
-    return commands
-
-
-def handle_dsv_types_except_source(type_, remainder, prefix):
-    commands = []
-    if type_ in (DSV_TYPE_SET, DSV_TYPE_SET_IF_UNSET):
-        try:
-            env_name, value = remainder.split(';', 1)
-        except ValueError:
-            raise RuntimeError(
-                "doesn't contain a semicolon separating the environment name "
-                'from the value')
-        try_prefixed_value = os.path.join(prefix, value) if value else prefix
-        if os.path.exists(try_prefixed_value):
-            value = try_prefixed_value
-        if type_ == DSV_TYPE_SET:
-            commands += _set(env_name, value)
-        elif type_ == DSV_TYPE_SET_IF_UNSET:
-            commands += _set_if_unset(env_name, value)
-        else:
-            assert False
-    elif type_ in (
-        DSV_TYPE_APPEND_NON_DUPLICATE,
-        DSV_TYPE_PREPEND_NON_DUPLICATE,
-        DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS
-    ):
-        try:
-            env_name_and_values = remainder.split(';')
-        except ValueError:
-            raise RuntimeError(
-                "doesn't contain a semicolon separating the environment name "
-                'from the values')
-        env_name = env_name_and_values[0]
-        values = env_name_and_values[1:]
-        for value in values:
-            if not value:
-                value = prefix
-            elif not os.path.isabs(value):
-                value = os.path.join(prefix, value)
-            if (
-                type_ == DSV_TYPE_PREPEND_NON_DUPLICATE_IF_EXISTS and
-                not os.path.exists(value)
-            ):
-                comment = f'skip extending {env_name} with not existing ' \
-                    f'path: {value}'
-                if _include_comments():
-                    commands.append(
-                        FORMAT_STR_COMMENT_LINE.format_map({'comment': comment}))
-            elif type_ == DSV_TYPE_APPEND_NON_DUPLICATE:
-                commands += _append_unique_value(env_name, value)
-            else:
-                commands += _prepend_unique_value(env_name, value)
-    else:
-        raise RuntimeError(
-            'contains an unknown environment hook type: ' + type_)
-    return commands
-
-
-env_state = {}
-
-
-def _append_unique_value(name, value):
-    global env_state
-    if name not in env_state:
-        if os.environ.get(name):
-            env_state[name] = set(os.environ[name].split(os.pathsep))
-        else:
-            env_state[name] = set()
-    # append even if the variable has not been set yet, in case a shell script sets the
-    # same variable without the knowledge of this Python script.
-    # later _remove_ending_separators() will cleanup any unintentional leading separator
-    extend = FORMAT_STR_USE_ENV_VAR.format_map({'name': name}) + os.pathsep
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': extend + value})
-    if value not in env_state[name]:
-        env_state[name].add(value)
-    else:
-        if not _include_comments():
-            return []
-        line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
-    return [line]
-
-
-def _prepend_unique_value(name, value):
-    global env_state
-    if name not in env_state:
-        if os.environ.get(name):
-            env_state[name] = set(os.environ[name].split(os.pathsep))
-        else:
-            env_state[name] = set()
-    # prepend even if the variable has not been set yet, in case a shell script sets the
-    # same variable without the knowledge of this Python script.
-    # later _remove_ending_separators() will cleanup any unintentional trailing separator
-    extend = os.pathsep + FORMAT_STR_USE_ENV_VAR.format_map({'name': name})
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': value + extend})
-    if value not in env_state[name]:
-        env_state[name].add(value)
-    else:
-        if not _include_comments():
-            return []
-        line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
-    return [line]
-
-
-# generate commands for removing prepended underscores
-def _remove_ending_separators():
-    # do nothing if the shell extension does not implement the logic
-    if FORMAT_STR_REMOVE_TRAILING_SEPARATOR is None:
-        return []
-
-    global env_state
-    commands = []
-    for name in env_state:
-        # skip variables that already had values before this script started prepending
-        if name in os.environ:
-            continue
-        commands += [
-            FORMAT_STR_REMOVE_LEADING_SEPARATOR.format_map({'name': name}),
-            FORMAT_STR_REMOVE_TRAILING_SEPARATOR.format_map({'name': name})]
-    return commands
-
-
-def _set(name, value):
-    global env_state
-    env_state[name] = value
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': value})
-    return [line]
-
-
-def _set_if_unset(name, value):
-    global env_state
-    line = FORMAT_STR_SET_ENV_VAR.format_map(
-        {'name': name, 'value': value})
-    if env_state.get(name, os.environ.get(name)):
-        line = FORMAT_STR_COMMENT_LINE.format_map({'comment': line})
-    return [line]
-
-
-if __name__ == '__main__':  # pragma: no cover
-    try:
-        rc = main()
-    except RuntimeError as e:
-        print(str(e), file=sys.stderr)
-        rc = 1
-    sys.exit(rc)
diff --git a/ros2/src/install/local_setup.bash b/ros2/src/install/local_setup.bash
deleted file mode 100644
index 03f00256c1a126057ca924bdd48ec74444b0cc10..0000000000000000000000000000000000000000
--- a/ros2/src/install/local_setup.bash
+++ /dev/null
@@ -1,121 +0,0 @@
-# generated from colcon_bash/shell/template/prefix.bash.em
-
-# This script extends the environment with all packages contained in this
-# prefix path.
-
-# a bash script is able to determine its own path if necessary
-if [ -z "$COLCON_CURRENT_PREFIX" ]; then
-  _colcon_prefix_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)"
-else
-  _colcon_prefix_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
-fi
-
-# function to prepend a value to a variable
-# which uses colons as separators
-# duplicates as well as trailing separators are avoided
-# first argument: the name of the result variable
-# second argument: the value to be prepended
-_colcon_prefix_bash_prepend_unique_value() {
-  # arguments
-  _listname="$1"
-  _value="$2"
-
-  # get values from variable
-  eval _values=\"\$$_listname\"
-  # backup the field separator
-  _colcon_prefix_bash_prepend_unique_value_IFS="$IFS"
-  IFS=":"
-  # start with the new value
-  _all_values="$_value"
-  _contained_value=""
-  # iterate over existing values in the variable
-  for _item in $_values; do
-    # ignore empty strings
-    if [ -z "$_item" ]; then
-      continue
-    fi
-    # ignore duplicates of _value
-    if [ "$_item" = "$_value" ]; then
-      _contained_value=1
-      continue
-    fi
-    # keep non-duplicate values
-    _all_values="$_all_values:$_item"
-  done
-  unset _item
-  if [ -z "$_contained_value" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      if [ "$_all_values" = "$_value" ]; then
-        echo "export $_listname=$_value"
-      else
-        echo "export $_listname=$_value:\$$_listname"
-      fi
-    fi
-  fi
-  unset _contained_value
-  # restore the field separator
-  IFS="$_colcon_prefix_bash_prepend_unique_value_IFS"
-  unset _colcon_prefix_bash_prepend_unique_value_IFS
-  # export the updated variable
-  eval export $_listname=\"$_all_values\"
-  unset _all_values
-  unset _values
-
-  unset _value
-  unset _listname
-}
-
-# add this prefix to the COLCON_PREFIX_PATH
-_colcon_prefix_bash_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_bash_COLCON_CURRENT_PREFIX"
-unset _colcon_prefix_bash_prepend_unique_value
-
-# check environment variable for custom Python executable
-if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then
-  if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then
-    echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist"
-    return 1
-  fi
-  _colcon_python_executable="$COLCON_PYTHON_EXECUTABLE"
-else
-  # try the Python executable known at configure time
-  _colcon_python_executable="/usr/bin/python3"
-  # if it doesn't exist try a fall back
-  if [ ! -f "$_colcon_python_executable" ]; then
-    if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then
-      echo "error: unable to find python3 executable"
-      return 1
-    fi
-    _colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"`
-  fi
-fi
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-_colcon_prefix_sh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$1"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# get all commands in topological order
-_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_bash_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh bash)"
-unset _colcon_python_executable
-if [ -n "$COLCON_TRACE" ]; then
-  echo "$(declare -f _colcon_prefix_sh_source_script)"
-  echo "# Execute generated script:"
-  echo "# <<<"
-  echo "${_colcon_ordered_commands}"
-  echo "# >>>"
-  echo "unset _colcon_prefix_sh_source_script"
-fi
-eval "${_colcon_ordered_commands}"
-unset _colcon_ordered_commands
-
-unset _colcon_prefix_sh_source_script
-
-unset _colcon_prefix_bash_COLCON_CURRENT_PREFIX
diff --git a/ros2/src/install/local_setup.ps1 b/ros2/src/install/local_setup.ps1
deleted file mode 100644
index 6f68c8dede9ed4ecb63a4eb6ac2a7450bd18ec3b..0000000000000000000000000000000000000000
--- a/ros2/src/install/local_setup.ps1
+++ /dev/null
@@ -1,55 +0,0 @@
-# generated from colcon_powershell/shell/template/prefix.ps1.em
-
-# This script extends the environment with all packages contained in this
-# prefix path.
-
-# check environment variable for custom Python executable
-if ($env:COLCON_PYTHON_EXECUTABLE) {
-  if (!(Test-Path "$env:COLCON_PYTHON_EXECUTABLE" -PathType Leaf)) {
-    echo "error: COLCON_PYTHON_EXECUTABLE '$env:COLCON_PYTHON_EXECUTABLE' doesn't exist"
-    exit 1
-  }
-  $_colcon_python_executable="$env:COLCON_PYTHON_EXECUTABLE"
-} else {
-  # use the Python executable known at configure time
-  $_colcon_python_executable="/usr/bin/python3"
-  # if it doesn't exist try a fall back
-  if (!(Test-Path "$_colcon_python_executable" -PathType Leaf)) {
-    if (!(Get-Command "python3" -ErrorAction SilentlyContinue)) {
-      echo "error: unable to find python3 executable"
-      exit 1
-    }
-    $_colcon_python_executable="python3"
-  }
-}
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-function _colcon_prefix_powershell_source_script {
-  param (
-    $_colcon_prefix_powershell_source_script_param
-  )
-  # source script with conditional trace output
-  if (Test-Path $_colcon_prefix_powershell_source_script_param) {
-    if ($env:COLCON_TRACE) {
-      echo ". '$_colcon_prefix_powershell_source_script_param'"
-    }
-    . "$_colcon_prefix_powershell_source_script_param"
-  } else {
-    Write-Error "not found: '$_colcon_prefix_powershell_source_script_param'"
-  }
-}
-
-# get all commands in topological order
-$_colcon_ordered_commands = & "$_colcon_python_executable" "$(Split-Path $PSCommandPath -Parent)/_local_setup_util_ps1.py" ps1
-
-# execute all commands in topological order
-if ($env:COLCON_TRACE) {
-  echo "Execute generated script:"
-  echo "<<<"
-  $_colcon_ordered_commands.Split([Environment]::NewLine, [StringSplitOptions]::RemoveEmptyEntries) | Write-Output
-  echo ">>>"
-}
-if ($_colcon_ordered_commands) {
-  $_colcon_ordered_commands.Split([Environment]::NewLine, [StringSplitOptions]::RemoveEmptyEntries) | Invoke-Expression
-}
diff --git a/ros2/src/install/local_setup.sh b/ros2/src/install/local_setup.sh
deleted file mode 100644
index 855f736b3ee9a3c775b2884509550af27b2fa703..0000000000000000000000000000000000000000
--- a/ros2/src/install/local_setup.sh
+++ /dev/null
@@ -1,137 +0,0 @@
-# generated from colcon_core/shell/template/prefix.sh.em
-
-# This script extends the environment with all packages contained in this
-# prefix path.
-
-# since a plain shell script can't determine its own path when being sourced
-# either use the provided COLCON_CURRENT_PREFIX
-# or fall back to the build time prefix (if it exists)
-_colcon_prefix_sh_COLCON_CURRENT_PREFIX="/home/robobin/robobin/ros2/src/install"
-if [ -z "$COLCON_CURRENT_PREFIX" ]; then
-  if [ ! -d "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX" ]; then
-    echo "The build time path \"$_colcon_prefix_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2
-    unset _colcon_prefix_sh_COLCON_CURRENT_PREFIX
-    return 1
-  fi
-else
-  _colcon_prefix_sh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
-fi
-
-# function to prepend a value to a variable
-# which uses colons as separators
-# duplicates as well as trailing separators are avoided
-# first argument: the name of the result variable
-# second argument: the value to be prepended
-_colcon_prefix_sh_prepend_unique_value() {
-  # arguments
-  _listname="$1"
-  _value="$2"
-
-  # get values from variable
-  eval _values=\"\$$_listname\"
-  # backup the field separator
-  _colcon_prefix_sh_prepend_unique_value_IFS="$IFS"
-  IFS=":"
-  # start with the new value
-  _all_values="$_value"
-  _contained_value=""
-  # iterate over existing values in the variable
-  for _item in $_values; do
-    # ignore empty strings
-    if [ -z "$_item" ]; then
-      continue
-    fi
-    # ignore duplicates of _value
-    if [ "$_item" = "$_value" ]; then
-      _contained_value=1
-      continue
-    fi
-    # keep non-duplicate values
-    _all_values="$_all_values:$_item"
-  done
-  unset _item
-  if [ -z "$_contained_value" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      if [ "$_all_values" = "$_value" ]; then
-        echo "export $_listname=$_value"
-      else
-        echo "export $_listname=$_value:\$$_listname"
-      fi
-    fi
-  fi
-  unset _contained_value
-  # restore the field separator
-  IFS="$_colcon_prefix_sh_prepend_unique_value_IFS"
-  unset _colcon_prefix_sh_prepend_unique_value_IFS
-  # export the updated variable
-  eval export $_listname=\"$_all_values\"
-  unset _all_values
-  unset _values
-
-  unset _value
-  unset _listname
-}
-
-# add this prefix to the COLCON_PREFIX_PATH
-_colcon_prefix_sh_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX"
-unset _colcon_prefix_sh_prepend_unique_value
-
-# check environment variable for custom Python executable
-if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then
-  if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then
-    echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist"
-    return 1
-  fi
-  _colcon_python_executable="$COLCON_PYTHON_EXECUTABLE"
-else
-  # try the Python executable known at configure time
-  _colcon_python_executable="/usr/bin/python3"
-  # if it doesn't exist try a fall back
-  if [ ! -f "$_colcon_python_executable" ]; then
-    if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then
-      echo "error: unable to find python3 executable"
-      return 1
-    fi
-    _colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"`
-  fi
-fi
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-_colcon_prefix_sh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$1"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# get all commands in topological order
-_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_sh_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh)"
-unset _colcon_python_executable
-if [ -n "$COLCON_TRACE" ]; then
-  echo "_colcon_prefix_sh_source_script() {
-    if [ -f \"\$1\" ]; then
-      if [ -n \"\$COLCON_TRACE\" ]; then
-        echo \"# . \\\"\$1\\\"\"
-      fi
-      . \"\$1\"
-    else
-      echo \"not found: \\\"\$1\\\"\" 1>&2
-    fi
-  }"
-  echo "# Execute generated script:"
-  echo "# <<<"
-  echo "${_colcon_ordered_commands}"
-  echo "# >>>"
-  echo "unset _colcon_prefix_sh_source_script"
-fi
-eval "${_colcon_ordered_commands}"
-unset _colcon_ordered_commands
-
-unset _colcon_prefix_sh_source_script
-
-unset _colcon_prefix_sh_COLCON_CURRENT_PREFIX
diff --git a/ros2/src/install/local_setup.zsh b/ros2/src/install/local_setup.zsh
deleted file mode 100644
index b6487102f245a7b5ddb2b1da158d6b99ddc91d8b..0000000000000000000000000000000000000000
--- a/ros2/src/install/local_setup.zsh
+++ /dev/null
@@ -1,134 +0,0 @@
-# generated from colcon_zsh/shell/template/prefix.zsh.em
-
-# This script extends the environment with all packages contained in this
-# prefix path.
-
-# a zsh script is able to determine its own path if necessary
-if [ -z "$COLCON_CURRENT_PREFIX" ]; then
-  _colcon_prefix_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)"
-else
-  _colcon_prefix_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
-fi
-
-# function to convert array-like strings into arrays
-# to workaround SH_WORD_SPLIT not being set
-_colcon_prefix_zsh_convert_to_array() {
-  local _listname=$1
-  local _dollar="$"
-  local _split="{="
-  local _to_array="(\"$_dollar$_split$_listname}\")"
-  eval $_listname=$_to_array
-}
-
-# function to prepend a value to a variable
-# which uses colons as separators
-# duplicates as well as trailing separators are avoided
-# first argument: the name of the result variable
-# second argument: the value to be prepended
-_colcon_prefix_zsh_prepend_unique_value() {
-  # arguments
-  _listname="$1"
-  _value="$2"
-
-  # get values from variable
-  eval _values=\"\$$_listname\"
-  # backup the field separator
-  _colcon_prefix_zsh_prepend_unique_value_IFS="$IFS"
-  IFS=":"
-  # start with the new value
-  _all_values="$_value"
-  _contained_value=""
-  # workaround SH_WORD_SPLIT not being set
-  _colcon_prefix_zsh_convert_to_array _values
-  # iterate over existing values in the variable
-  for _item in $_values; do
-    # ignore empty strings
-    if [ -z "$_item" ]; then
-      continue
-    fi
-    # ignore duplicates of _value
-    if [ "$_item" = "$_value" ]; then
-      _contained_value=1
-      continue
-    fi
-    # keep non-duplicate values
-    _all_values="$_all_values:$_item"
-  done
-  unset _item
-  if [ -z "$_contained_value" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      if [ "$_all_values" = "$_value" ]; then
-        echo "export $_listname=$_value"
-      else
-        echo "export $_listname=$_value:\$$_listname"
-      fi
-    fi
-  fi
-  unset _contained_value
-  # restore the field separator
-  IFS="$_colcon_prefix_zsh_prepend_unique_value_IFS"
-  unset _colcon_prefix_zsh_prepend_unique_value_IFS
-  # export the updated variable
-  eval export $_listname=\"$_all_values\"
-  unset _all_values
-  unset _values
-
-  unset _value
-  unset _listname
-}
-
-# add this prefix to the COLCON_PREFIX_PATH
-_colcon_prefix_zsh_prepend_unique_value COLCON_PREFIX_PATH "$_colcon_prefix_zsh_COLCON_CURRENT_PREFIX"
-unset _colcon_prefix_zsh_prepend_unique_value
-unset _colcon_prefix_zsh_convert_to_array
-
-# check environment variable for custom Python executable
-if [ -n "$COLCON_PYTHON_EXECUTABLE" ]; then
-  if [ ! -f "$COLCON_PYTHON_EXECUTABLE" ]; then
-    echo "error: COLCON_PYTHON_EXECUTABLE '$COLCON_PYTHON_EXECUTABLE' doesn't exist"
-    return 1
-  fi
-  _colcon_python_executable="$COLCON_PYTHON_EXECUTABLE"
-else
-  # try the Python executable known at configure time
-  _colcon_python_executable="/usr/bin/python3"
-  # if it doesn't exist try a fall back
-  if [ ! -f "$_colcon_python_executable" ]; then
-    if ! /usr/bin/env python3 --version > /dev/null 2> /dev/null; then
-      echo "error: unable to find python3 executable"
-      return 1
-    fi
-    _colcon_python_executable=`/usr/bin/env python3 -c "import sys; print(sys.executable)"`
-  fi
-fi
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-_colcon_prefix_sh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$1"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# get all commands in topological order
-_colcon_ordered_commands="$($_colcon_python_executable "$_colcon_prefix_zsh_COLCON_CURRENT_PREFIX/_local_setup_util_sh.py" sh zsh)"
-unset _colcon_python_executable
-if [ -n "$COLCON_TRACE" ]; then
-  echo "$(declare -f _colcon_prefix_sh_source_script)"
-  echo "# Execute generated script:"
-  echo "# <<<"
-  echo "${_colcon_ordered_commands}"
-  echo "# >>>"
-  echo "unset _colcon_prefix_sh_source_script"
-fi
-eval "${_colcon_ordered_commands}"
-unset _colcon_ordered_commands
-
-unset _colcon_prefix_sh_source_script
-
-unset _colcon_prefix_zsh_COLCON_CURRENT_PREFIX
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/PKG-INFO b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/PKG-INFO
deleted file mode 100644
index 59b425a79a72e98ee9bcafffada085b85d328236..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/PKG-INFO
+++ /dev/null
@@ -1,7 +0,0 @@
-Metadata-Version: 2.1
-Name: robobin
-Version: 0.0.0
-Summary: TODO: Package description
-Maintainer: paulw
-Maintainer-email: plw1g21@soton.ac.uk
-License: TODO: License declaration
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/SOURCES.txt b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/SOURCES.txt
deleted file mode 100644
index 2fe204918a694fd60d88ab57b64a95b9b52c6acb..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/SOURCES.txt
+++ /dev/null
@@ -1,22 +0,0 @@
-package.xml
-setup.cfg
-setup.py
-../build/robobin/robobin.egg-info/PKG-INFO
-../build/robobin/robobin.egg-info/SOURCES.txt
-../build/robobin/robobin.egg-info/dependency_links.txt
-../build/robobin/robobin.egg-info/entry_points.txt
-../build/robobin/robobin.egg-info/requires.txt
-../build/robobin/robobin.egg-info/top_level.txt
-../build/robobin/robobin.egg-info/zip-safe
-launch/robobin_launch.py
-resource/robobin
-robobin/__init__.py
-robobin/api_node.py
-robobin/motor_control_node.py
-robobin/uwb_navigation_node.py
-robobin/helpers/__init__.py
-robobin/helpers/connection_manager.py
-robobin/helpers/message_handler.py
-test/test_copyright.py
-test/test_flake8.py
-test/test_pep257.py
\ No newline at end of file
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/dependency_links.txt b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/dependency_links.txt
deleted file mode 100644
index 8b137891791fe96927ad78e64b0aad7bded08bdc..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/dependency_links.txt
+++ /dev/null
@@ -1 +0,0 @@
-
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/entry_points.txt b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/entry_points.txt
deleted file mode 100644
index a569c6445838df1de986e4c1140c21af9733dc9c..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/entry_points.txt
+++ /dev/null
@@ -1,4 +0,0 @@
-[console_scripts]
-api_node = robobin.api_node:main
-motor_control_node = robobin.motor_control_node:main
-uwb_navigation_node = robobin.uwb_navigation_node:main
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/requires.txt b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/requires.txt
deleted file mode 100644
index 49fe098d9e6bccd89482b34510da60ab28556880..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/requires.txt
+++ /dev/null
@@ -1 +0,0 @@
-setuptools
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/top_level.txt b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/top_level.txt
deleted file mode 100644
index 2ca7c929754f574fe60649fed5f1333479af4ef7..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/top_level.txt
+++ /dev/null
@@ -1 +0,0 @@
-robobin
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/zip-safe b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/zip-safe
deleted file mode 100644
index 8b137891791fe96927ad78e64b0aad7bded08bdc..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info/zip-safe
+++ /dev/null
@@ -1 +0,0 @@
-
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__init__.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__init__.py
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/__init__.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/__init__.cpython-312.pyc
deleted file mode 100644
index 998c28a922da748259570304b190ba527f7ca915..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/__init__.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/api_node.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/api_node.cpython-312.pyc
deleted file mode 100644
index 641931ecbff4e6674598a43fbd8b91e1acc0da46..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/api_node.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/control_feedback.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/control_feedback.cpython-312.pyc
deleted file mode 100644
index 1e435b8c0289e4cfa134234abe99960f7375fd65..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/control_feedback.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/encoder.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/encoder.cpython-312.pyc
deleted file mode 100644
index 7cb8382db94f1e7e04c7a59acc189e0c5a4424d3..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/encoder.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/imu_node.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/imu_node.cpython-312.pyc
deleted file mode 100644
index bb19218991120a6e0724366c747e1818452655ab..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/imu_node.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/motor_control_node.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/motor_control_node.cpython-312.pyc
deleted file mode 100644
index 971a073d799fd933f6e9568db894f906b43a2971..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/motor_control_node.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_navigation_node.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_navigation_node.cpython-312.pyc
deleted file mode 100644
index d285df03ca3e93994ca86b25c6f506071f7a3742..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_navigation_node.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_pathing_node.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_pathing_node.cpython-312.pyc
deleted file mode 100644
index 3e6915f3d140dacbf90fbdb8150f1a01eac557e6..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__pycache__/uwb_pathing_node.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/api_node.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/api_node.py
deleted file mode 100644
index d83622c7d0d85e12c642f1fad0dfe9b411b6dd60..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/api_node.py
+++ /dev/null
@@ -1,106 +0,0 @@
-
-# robobin/api_node.py
-from .helpers.message_handler import MessageHandler
-from .helpers.connection_manager import ConnectionManager
-
-from geometry_msgs.msg import Twist
-from geometry_msgs.msg import Point
-from std_msgs.msg import String
-import rclpy
-from rclpy.node import Node
-
-class ApiNode(Node):
-    def __init__(self):
-        super().__init__('api_node')
-        self.get_logger().info("ApiNode has been started.")
-
-        self.publisher_topics = {
-            "cmd_vel": self.create_publisher(Twist, '/cmd_vel', 10),
-            "nav_send": self.create_publisher(Twist, '/nav_send', 10), 
-            "nav_command": self.create_publisher(String, '/nav_command', 10),
-        }
-        self.location_subscriber = self.create_subscription(
-            Point,  # Message type
-            '/tag1_location',  # Topic
-            self.handle_location_update,  # Callback
-            10  # QoS depth
-        )
-        self.mode = "Manual"
-        self.called_locations = [] # List of  pairs of ip address and location
-        self.message_handler = MessageHandler(self)
-        self.connection_manager = ConnectionManager(self)
-
-        self.connection_manager.start()
-        self.get_logger().info("Connection manager started.")
-    def handle_client_connection(self, client_socket):
-        """Handles incoming TCP client connections."""
-        try:
-            while True:
-                data = client_socket.recv(1024).decode()
-                if not data:
-                    break
-                self.get_logger().info(f"Received data: {data}")
-                test = data.split(" ", 1)
-                self.get_logger().info(f"Received command: {test[0]}")
-                result = self.message_handler.handle_message(client_socket, data)
-        
-                # Check if the result is not None
-                if result is not None:
-                    topic, message = result  # Safely unpack after checking
-                    if topic is not None:
-                        self.get_logger().info(f"Publishing to topic: {topic}")
-                        self.publish_to_topic(topic, message)
-        finally:
-            client_socket.close()
-            self.get_logger().info("Client disconnected.")
-    def publish_to_topic(self, topic, message):
-        self.get_logger().info(f"Publishing to topic: {topic}")
-        """Publishes the message to the specified topic."""
-        if topic in self.publisher_topics:
-            publisher = self.publisher_topics[topic]
-
-            # Check if the topic is 'cmd_vel' and format the message as a Twist message
-            if topic == "cmd_vel" and isinstance(message, tuple):
-                linear_x, angular_z = message
-                twist_msg = Twist()
-                twist_msg.linear.x = linear_x
-                twist_msg.linear.y = 0.0
-                twist_msg.linear.z = 0.0
-                twist_msg.angular.x = 0.0
-                twist_msg.angular.y = 0.0
-                twist_msg.angular.z = angular_z
-
-                publisher.publish(twist_msg)
-                self.get_logger().info(f"Published to {topic}: linear_x={linear_x}, angular_z={angular_z}")
-            elif topic == "nav_command" and isinstance(message, str):
-                self.get_logger().info(f"Published to {topic}: {message}")
-                publisher.publish(String(data=message))
-            else:
-                self.get_logger().warning(f"Unhandled message type for topic: {topic}")
-        else:
-            self.get_logger().warning(f"Unknown topic: {topic}")
-    def handle_location_update(self, msg):
-        self.get_logger().info("Received updated location.")
-        self.get_logger().info(f"Received updated location: x={msg.x:.2f}, y={msg.y:.2f}")
-        """Callback for the /tag1_location topic."""
-        x = msg.x
-        y = msg.y
-        self.connection_manager.set_location(x, y)
-        self.get_logger().info(f"Received updated location: x={x:.2f}, y={y:.2f}")
-    def shutdown(self):
-        """Stops the connection manager."""
-        self.connection_manager.stop()
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = ApiNode()
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        node.shutdown()
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py
deleted file mode 100644
index 78a1edb74b03fbdf991c9e38c1b8980ee52b3945..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py
+++ /dev/null
@@ -1,320 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Twist
-from std_msgs.msg import Int64, Float64
-from gpiozero import PWMOutputDevice, DigitalOutputDevice
-import time
-from rclpy.clock import Clock
-from rclpy.time import Time
-import bisect
-
-
-
-# Example of how you could implement a simple PID controller
-class PIDController:
-    def __init__(self, kp, ki, kd):
-        self.kp = kp
-        self.ki = ki
-        self.kd = kd
-        self.prev_error = 0
-        self.integral = 0
-
-    def reset(self):
-        self.prev_error = 0
-        self.integral = 0
-
-    def calculate(self, error, dt):
-        self.integral += error * dt
-        derivative = (error - self.prev_error) / dt 
-        output = self.kp * error + self.ki * self.integral + self.kd * derivative
-        self.prev_error = error
-        return output
-
-
-
-
-class MotorControlNode(Node):
-    def __init__(self):
-        super().__init__('control_feedback_node')
-
-        # Initialize encoder values
-        self.encoder_left_steps = 0
-        self.encoder_right_steps = 0
-
-        # Desired speeds from cmd_vel
-        self.desired_linear_speed = 0.0
-        self.desired_angular_speed = 0.0
-
-        self.prev_left_steps = 0
-        self.prev_right_steps = 0
-
-        self.left_pwm = 0
-        self.right_pwm = 0
-
-        self.prev_desired_speed = 0.0
-
-
-        #Time
-        self.prev_time = time.time()
-        #self.prev_time = self.get_clock().now
-
-        
-        # Robot parameters
-        self.wheel_base = 0.40  
-        self.encoder_steps_per_rotation = 310  
-        self.wheel_radius = 0.075 
-
-        # Initialize the motors
-        self.motor = Motor(self,14,15,18, 17, 22, 27)
-
-        # PID controllers
-        self.pid_left_forward = PIDController(kp=0.5, ki=0.0, kd=0.001)
-        self.pid_right_forward = PIDController(kp=0.525, ki=0.0, kd=0.001)
-
-        self.pid_left_backward = PIDController(kp=0.525, ki=0.0, kd=0.001)
-        self.pid_right_backward = PIDController(kp=0.5, ki=0.0, kd=0.001)
-
-
-
-
-        # Subscribe to cmd_vel topic
-        self.subscription = self.create_subscription(
-            Twist,
-            '/cmd_vel',
-            self.cmd_vel_callback,
-            10
-        )
-
-        # Subscribe to encoder data
-        self.left_encoder_sub = self.create_subscription(
-            Int64,
-            'left_wheel_steps',
-            self.left_encoder_callback,
-            10
-        )
-        self.right_encoder_sub = self.create_subscription(
-            Int64,
-            'right_wheel_steps',
-            self.right_encoder_callback,
-            10
-        )
-
-        self.left_actual_speed_pub = self.create_publisher(Float64, 'left_actual_wheel_speed', 10)
-        self.right_actual_speed_pub = self.create_publisher(Float64, 'right_actual_wheel_speed', 10)
-        self.desired_speed_pub = self.create_publisher(Float64, 'desired_wheel_speed', 10)
-
-        # Timer to update motor speeds
-        self.control_timer = self.create_timer(0.1, self.control_loop)
-
-        self.get_logger().info('Motor control node with encoder feedback has been started.')
-
-    def cmd_vel_callback(self, msg):
-        # Store desired speeds
-        self.desired_linear_speed = msg.linear.x  # Forward/backward speed
-        self.desired_angular_speed = msg.angular.z  # Turning rate
-
-        # if (self.desired_linear_speed >= 0 and self.prev_desired_speed < 0) or (self.desired_linear_speed < 0 and self.prev_desired_speed >= 0):
-
-        #     self.pid_left_forward.reset()
-        #     self.pid_right_forward.reset()
-        #     self.pid_left_backward.reset()
-        #     self.pid_right_backward.reset()
-
-
-
-        
-
-        self.prev_desired_speed = self.desired_linear_speed
-
-    def left_encoder_callback(self, msg):
-        self.encoder_left_steps = msg.data
-
-    def right_encoder_callback(self, msg):
-        self.encoder_right_steps = msg.data
-
-    
-    def control_loop(self):
-
-        if self.desired_linear_speed >= 0:
-            # Forward motion
-            left_pid = self.pid_left_forward
-            right_pid = self.pid_right_forward
-        else:
-            # Backward motion
-            left_pid = self.pid_left_backward
-            right_pid = self.pid_right_backward
-
-        if (self.desired_linear_speed == 0) and (self.desired_angular_speed == 0):
-            self.stop_motors()
-            self.pid_left_forward.reset()
-            self.pid_right_forward.reset()
-            self.pid_left_backward.reset()
-            self.pid_right_backward.reset()
-            self.left_pwm =0
-            self.right_pwm =0
-            return
-
-
-
-
-        #Calculate the actual speed
-        #-------------------------------
-        # Calculate elapsed time
-        current_time = time.time()
-        #dt = current_time - self.prev_time
-        dt = max(current_time - self.prev_time, 0.01)  # Prevent dt from being too small
-        #dt = max(current_time - self.prev_time, 1e-6)  # Avoid zero or too small dt
-        if dt == 0:
-            return
-        self.prev_time = current_time
-
-        # self.prev_time = self.get_clock().now()
-        # current_time = self.get_clock().now()
-        # dt = (current_time - self.prev_time).to_sec()
-        # if dt <= 0.0:
-        #     return
-        # self.prev_time = current_time
-
-        #Actual Speed calculation
-        #------------------------------------
-        # Calculate change in encoder steps
-        delta_left_steps = self.encoder_left_steps - self.prev_left_steps
-        delta_right_steps = self.encoder_right_steps - self.prev_right_steps
-
-        self.prev_left_steps = self.encoder_left_steps
-        self.prev_right_steps = self.encoder_right_steps
-
-        # Calculate rotational speeds (RPS)
-        left_rps = delta_left_steps / (self.encoder_steps_per_rotation * dt)
-        right_rps = delta_right_steps / (self.encoder_steps_per_rotation * dt)
-
-        # Convert to linear speed (m/s)
-        left_speed_actual = left_rps * 2 * 3.14159 * self.wheel_radius
-        right_speed_actual = right_rps * 2 * 3.14159 * self.wheel_radius
-
-
-
-        #Desired Speed calculation
-        #------------------------------------
-        # Desired speeds for left and right wheels
-        left_speed_desired = self.desired_linear_speed - (self.desired_angular_speed * self.wheel_base / 2.0)
-        right_speed_desired = self.desired_linear_speed + (self.desired_angular_speed * self.wheel_base / 2.0)
-
-
-
-        # Speed Errors calculation
-        #------------------------------------
-        left_error = left_speed_desired - left_speed_actual
-        right_error = right_speed_desired - right_speed_actual
-
- 
-
-        # Use PID controllers for left and right wheels
-        left_pwm_error = left_pid.calculate(left_error, dt)
-        right_pwm_error = right_pid.calculate(right_error, dt)
-
-        self.left_pwm +=   left_pwm_error
-        self.right_pwm +=  right_pwm_error
-
-
-
-        # Ensure PWM values are within [-1, 1]
-        left_pwm = max(-1, min(1, self.left_pwm))
-        right_pwm = max(-1, min(1, self.right_pwm))
-
-        # Apply PWM values to motors
-        self.motor.set_pwm(left_pwm, right_pwm)
-
-        
-
-
-        # Publish actual speeds
-        left_actual_speed_msg = Float64()
-        left_actual_speed_msg.data = left_speed_actual
-        self.left_actual_speed_pub.publish(left_actual_speed_msg)
-
-        right_actual_speed_msg = Float64()
-        right_actual_speed_msg.data = right_speed_actual
-        self.right_actual_speed_pub.publish(right_actual_speed_msg)
-
-        desired_speed_msg = Float64()
-        desired_speed_msg.data = right_speed_desired
-        self.desired_speed_pub.publish(desired_speed_msg)
-
-
-        # Debugging info
-        # self.get_logger().info(f'Left PWM IN: {self.left_pwm:.2f}, Right PWM IN: {right_pwm:.2f}')
-        # self.get_logger().info(f'Left Speed Actual: {left_speed_actual:.2f}, Right Speed Actual: {right_speed_actual:.2f}')
-        # self.get_logger().info(f'Left Error: {left_error:.2f}, Right Error: {left_pwm_error:.2f}')
-        # self.get_logger().info(f'Left_speed_desired: {left_speed_desired:.2f}, Right_speed_desired: {right_speed_desired:.2f}')
-        # self.get_logger().info('-----------------------------------------------------------------')
-
-
-    def stop_motors(self):
-        self.motor.stop()
-        # self.get_logger().info('Motors have been stopped.')
-
-class Motor:
-    def __init__(self,node, EnaA, In1A, In2A, EnaB, In1B, In2B):
-
-        self.node = node
-        # Left motor control pins
-        self.pwmA = PWMOutputDevice(EnaA)
-        self.in1A = DigitalOutputDevice(In1A)
-        self.in2A = DigitalOutputDevice(In2A)
-
-        # Right motor control pins
-        self.pwmB = PWMOutputDevice(EnaB)
-        self.in1B = DigitalOutputDevice(In1B)
-        self.in2B = DigitalOutputDevice(In2B)
-
-    def set_pwm(self, left_pwm, right_pwm):
-
-        #Deadband to prevent the motors from responding to very small PWM values that could cause jitter.
-        DEADZONE = 0.002
-
-        if abs(left_pwm) < DEADZONE:
-            self.pwmA.value = 0
-            self.in1A.off()
-            self.in2A.off()
-        else:
-            self.pwmA.value = abs(left_pwm)
-            self.in1A.value = left_pwm >  0
-            self.in2A.value = left_pwm < 0
-
-        if abs(right_pwm) < DEADZONE:
-            self.pwmB.value = 0
-            self.in1B.off()
-            self.in2B.off()
-        else:
-            self.pwmB.value = abs(right_pwm)
-            self.in1B.value = right_pwm >  0
-            self.in2B.value = right_pwm < 0
-
-        #self.node.get_logger().info(f"Left Motor PWM: Speed={left_pwm}, Right Motor PWM: Speed={right_pwm}")
-
-    def stop(self):
-        # Stop both motors
-        self.pwmA.value = 0
-        self.pwmB.value = 0
-        self.in1A.off()
-        self.in2A.off()
-        self.in1B.off()
-        self.in2B.off()
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = MotorControlNode()
-
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.stop_motors()
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/encoder.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/encoder.py
deleted file mode 100644
index f646d3dc16cc781b870f52bdbbfc5b5e6e3cbcd0..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/encoder.py
+++ /dev/null
@@ -1,63 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from std_msgs.msg import Int64
-from gpiozero import RotaryEncoder, InputDevice
-
-
-
-class EncoderReaderNode(Node):
-    def __init__(self):
-        super().__init__('encoder_reader_node')
-
-        motor1A = 5
-        motor1B = 6
-        motor2A = 20
-        motor2B = 21
-
-        self.encoder_left = RotaryEncoder(a = motor1A,b = motor1B, max_steps=0)
-        self.encoder_right = RotaryEncoder(a = motor2A,b = motor2B, max_steps=0)
-
-        # Publishers for encoder steps
-        self.left_encoder_pub = self.create_publisher(Int64, 'left_wheel_steps', 10)
-        self.right_encoder_pub = self.create_publisher(Int64, 'right_wheel_steps', 10)
-
-        # Timer to read encoders
-        self.timer = self.create_timer(0.1, self.publish_encoder_steps)
-
-        self.get_logger().info('Encoder reader node has been started.')
-
-    def publish_encoder_steps(self):
-        # Read encoder steps
-        left_steps = self.encoder_left.steps
-        right_steps = -(self.encoder_right.steps)
-
-        # Create messages
-        left_msg = Int64()
-        left_msg.data = left_steps
-
-        right_msg = Int64()
-        right_msg.data = right_steps
-
-        # Publish messages
-        self.left_encoder_pub.publish(left_msg)
-        self.right_encoder_pub.publish(right_msg)
-
-        # Log the steps
-        #self.get_logger().info(f'Left Steps: {left_steps}, Right Steps: {right_steps}')
-
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = EncoderReaderNode()
-
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/__init__.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/__init__.cpython-312.pyc
deleted file mode 100644
index 8f57a6850588e0b530ec37b4f438b1134b9902ef..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/__init__.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/connection_manager.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/connection_manager.cpython-312.pyc
deleted file mode 100644
index da1f7674650cb03554aea5f4d926b5c9ea7533f7..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/connection_manager.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/graph_maker.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/graph_maker.cpython-312.pyc
deleted file mode 100644
index 32a8c2cc3a530ad7871ed1906033649575c9ffa9..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/graph_maker.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/message_handler.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/message_handler.cpython-312.pyc
deleted file mode 100644
index f7f884c6d27c7a5a35eec3f10f8b6c2df32e3dd6..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/message_handler.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/realtime_location_cli_only.cpython-312.pyc b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/realtime_location_cli_only.cpython-312.pyc
deleted file mode 100644
index d64f7c0eab5d8e435c4d2bdd742e9e823b7a705b..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__pycache__/realtime_location_cli_only.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py
deleted file mode 100644
index 0fb010b26ca2d962796eb49eee48ab8836705d9f..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py
+++ /dev/null
@@ -1,88 +0,0 @@
-import socket
-import threading
-import time
-import json
-
-class ConnectionManager:
-    def __init__(self, api_node, udp_ip="255.255.255.255", udp_port=5005, listen_port=5006):
-        self.api_node = api_node
-        self.UDP_IP = udp_ip
-        self.UDP_PORT = udp_port
-        self.LISTEN_PORT = listen_port
-        self.stop_event = threading.Event()
-        self.location = [0, 0]  # At some point, this will be retrieved from the navigation node
-                
-    def start(self):
-        """Starts listening for connections and broadcasting presence."""
-        self.listen_thread = threading.Thread(target=self.listen_for_connections)
-        self.broadcast_thread = threading.Thread(target=self.broadcast_presence)
-        self.listen_thread.start()
-        self.broadcast_thread.start()
-
-    def listen_for_connections(self):
-        """Listens for UDP 'CONNECT' messages and sets up TCP connections."""
-        udp_sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
-        udp_sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
-        udp_sock.bind(('', self.LISTEN_PORT))
-
-        while not self.stop_event.is_set():
-            try:
-                data, addr = udp_sock.recvfrom(1024)
-                if data.decode() == "CONNECT":
-                    self.api_node.get_logger().info(f"Received CONNECT message from {addr}")
-                    tcp_sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
-                    tcp_sock.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
-                    tcp_sock.bind(('', self.LISTEN_PORT))
-                    tcp_sock.listen(1)
-                    client_socket, client_addr = tcp_sock.accept()
-                    self.api_node.get_logger().info(f"Client connected from {client_addr}")
-                    threading.Thread(target=self.api_node.handle_client_connection, args=(client_socket,)).start()
-            except socket.timeout:
-                continue
-            except OSError:
-                break
-
-        udp_sock.close()
-        print("Stopped listening for connections.")
-
-    def broadcast_presence(self):
-        """Broadcasts presence periodically over UDP."""
-        sock = socket.socket(socket.AF_INET, socket.SOCK_DGRAM)
-        sock.setsockopt(socket.SOL_SOCKET, socket.SO_BROADCAST, 1)
-
-        while not self.stop_event.is_set():
-            try:
-                mode = self.api_node.mode
-                
-                # JSON-formatted message
-                message = {
-                    "type": "ROBOBIN_PRESENT",
-                    "data": {
-                        "Location": self.location,
-                        "Mode": mode,
-                       
-                    }
-                }
-
-                # Serialize the JSON message to a string
-                json_message = json.dumps(message).encode('utf-8')
-
-                # Send the JSON message over UDP
-                sock.sendto(json_message, (self.UDP_IP, self.UDP_PORT))
-                self.api_node.get_logger().info("Broadcasting JSON presence.")
-                self.api_node.get_logger().info(f"Location: {self.location}, Mode: {mode}")
-                time.sleep(2)
-            except OSError:
-                break
-
-        sock.close()
-        self.api_node.get_logger().info("Stopped broadcasting presence.")
-    def set_location(self, x, y):
-        """Sets the location of the robot."""
-        self.location = [x, y]
-    def stop(self):
-        """Stops the connection manager."""
-        self.stop_event.set()
-    
-if __name__ == "__main__":
-    ConnectionManager(None).start()
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py
deleted file mode 100644
index c197c10b7eea1a63721b6cf40554a57b79c13d75..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py
+++ /dev/null
@@ -1,112 +0,0 @@
-import json
-import time
-import os
-from realtime_location_cli_only import AnchorTagCLI
-
-class GraphMaker:
-    def __init__(self, port="COM11", testing=False):
-        self.app = AnchorTagCLI(port=port, testing=testing)
-        self.graph = {
-            "name": "Lab 1 Extended",
-            "nodes": [],
-            "connections": []
-        }
-        self.previous_node_index = None
-
-    def call_bpm_and_store_anchors(self):
-        self.app.call_bpm()
-        for name, (x, y) in self.app.anchors.items():
-            self.graph["nodes"].append({
-                "name": name,
-                "x": x,
-                "y": y
-            })
-
-        # Initialize connections matrix with False
-        num_nodes = len(self.graph["nodes"])
-        self.graph["connections"] = [[False] * num_nodes for _ in range(num_nodes)]
-
-        print("Anchor coordinates stored successfully.")
-
-    def start_session(self):
-        print("Waiting for 'start' command...")
-        while True:
-            user_input = input("Enter 'start' to begin adding nodes or 'quit' to exit: ").strip().lower()
-            if user_input == "start":
-                print("Session started. Type 'save' to add nodes, 'finish' to save the graph, or 'quit' to exit.")
-                break
-            elif user_input == "quit":
-                print("Exiting...")
-                exit()
-
-    def add_node_and_connect(self):
-        print(self.app.tag_distances)
-        distances = self.app.serial_buffer.getRangingDistances()
-
-        tag1_x, tag1_y = self.app.update_distances_and_calculate_tags()
-        print(f"{tag1_x}, {tag1_y}")
-        if tag1_x is None or tag1_y is None:
-            print("Failed to determine tag position. Skipping node creation.")
-            return
-
-        new_node_index = len(self.graph["nodes"])
-
-        # Add new node
-        self.graph["nodes"].append({
-            "name": f"Node{new_node_index+1}",
-            "x": tag1_x,
-            "y": tag1_y
-        })
-
-        # Dynamically resize the connections matrix
-        for row in self.graph["connections"]:
-            row.append(False)  # Add a column for the new node
-        self.graph["connections"].append([False] * (new_node_index + 1))  # Add a new row
-
-        # Update connections
-        if self.previous_node_index is not None:
-            self.graph["connections"][self.previous_node_index][new_node_index] = True
-            self.graph["connections"][new_node_index][self.previous_node_index] = True
-
-        self.previous_node_index = new_node_index
-
-        print(f"Node {new_node_index+1} added at ({tag1_x:.2f}, {tag1_y:.2f}).")
-
-    def save_graph(self):
-        directory = r"D:\Github\robobin\ros2\src\robobin\robobin\graphs" #Replace with whereever your graphs folder is in the ros2 workspace
-        os.makedirs(directory, exist_ok=True)  # Create the directory if it doesn't exist
-        file_path = os.path.join(directory, "graph.json")
-        with open(file_path, "w") as f:
-            json.dump(self.graph, f, indent=2)
-        print(f"Graph saved to '{file_path}'.")
-
-
-    def run(self):
-        while True:
-            user_input = input("Enter command ('bpm', 'start', 'save', 'finish', 'quit'): ").strip().lower()
-            if user_input == "bpm":
-                self.call_bpm_and_store_anchors()
-            elif user_input == "start":
-                self.start_session()
-                while True:
-                    user_input = input("Enter 'save' to add a node, 'finish' to save and exit, or 'quit' to exit: ").strip().lower()
-                    if user_input == "save":
-                        self.add_node_and_connect()
-                    elif user_input == "finish":
-                        self.save_graph()
-                        print("Session finished.")
-                        exit()
-                    elif user_input == "quit":
-                        print("Exiting without saving.")
-                        exit()
-                    else:
-                        print("Invalid command. Try 'save', 'finish', or 'quit'.")
-            elif user_input == "quit":
-                print("Exiting...")
-                break
-            else:
-                print("Invalid command. Try 'bpm', 'start', 'save', 'finish', or 'quit'.")
-
-if __name__ == "__main__":
-    graph_maker = GraphMaker(port="/dev/tty.usbmodem14101", testing=False)
-    graph_maker.run()
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py
deleted file mode 100644
index 72ca4a5795a8a5190e77e67e41b42bfa8d4e3a11..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py
+++ /dev/null
@@ -1,193 +0,0 @@
-# robobin/message_handler.py
-import time
-import json
-
-import os
-class MessageHandler:
-    def __init__(self, api_node, testing=False):
-        self.api_node = api_node
-        self.testing = testing
-        self.handlers = {
-            "PING": self.handle_ping,
-            "TIME": self.handle_time_request,
-            "MANUALCTRL": self.handle_manual_control,
-            "SETMODE": self.handle_set_mode,
-            "STOP": self.handle_stop,
-            "CALLME": self.handle_call_me,
-            "BPM": self.handle_call_bpm,
-            "REQMAP": self.handle_request_map,
-        }
-
-    def handle_message(self, client_socket, raw_message):
-        """Parses the incoming message and routes the command to the appropriate handler."""
-        command, *args = raw_message.split(" ", 1)
-        #self.api_node.logger.info(f"Received command: {command}")
-        #self.api_node.logger.info(f"Received arguments: {args}")
-        data = args[0] if args else None
-        handler = self.handlers.get(command, self.handle_unknown_message)
-        return handler(client_socket, data)
-    
-    def handle_call_me(self, client_socket, message):
-        #Message says  CALLME,(212.9638, 283.98108), extract location and ip address
-        if client_socket is None:
-            ip = "Fake IP"
-        else:
-            ip = client_socket.getpeername()[0]
-        print(message)
-        location = message.strip() # Remove parentheses
-        location = f"{location}"  # Add parentheses back for proper formatting
-        
-        for existing_ip, _ in self.api_node.called_locations:
-            if existing_ip == ip:
-                client_socket.sendall(b"User already requested location")
-                return None  # IP already in the list, exit early
-
-        self.api_node.called_locations.append((ip, location))
-    
-        response = f"Queue Position = {len(self.api_node.called_locations)-1}".encode()
-        client_socket.sendall(response)
-        print("nav_command", location)
-        return "nav_command", location
-    
-    def handle_stop(self, client_socket, _):
-        """Handles the STOP command."""
-        response = b"Stopping the robot"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        return "cmd_vel", (0.0, 0.0)
-    
-    def handle_ping(self, client_socket, _):
-        """Responds with a PONG message."""
-        response = b"PONG"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-
-        return None
-    def handle_set_mode(self, client_socket, message):
-        """Handles mode setting commands."""
-        response = f"Setting mode to {message}".encode()
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        self.api_node.mode = message
-        return None
-    def handle_time_request(self, client_socket, _):
-        """Sends the current server time."""
-        response = time.ctime().encode()
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-
-        return None
-    def handle_call_bpm(self, client_socket, _):
-        """Handles the CALLBPM command."""
-        response = b"Calling BPM, Graph will be reset"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-
-        return "nav_command","BPM"
-    def handle_manual_control(self, client_socket, message):
-        """Handles manual control commands: W, A, S, D."""
-        # W: linear.x = 0.5, angular.z = 0
-        # A: linear.x = 0, angular.z = 0.5
-        # S: linear.x = -0.5, angular.z = 0
-        # D: linear.x = 0, angular.z = -0.5
-        
-        directions = {
-            "W": (0.5, 0),    # Move forward
-            "A": (0, 0.5),    # Turn left
-            "S": (-0.5, 0),   # Move backward
-            "D": (0, -0.5)    # Turn right
-        }
-        
-        # Get direction data and ensure it's a tuple of floats
-        raw_response_data = directions.get(message.strip().upper(), (0, 0))
-        response_data = (float(raw_response_data[0]), float(raw_response_data[1]))  # Explicitly cast to float
-        
-        # Send feedback to the client
-        response = f"Manual control command received: {response_data}".encode()
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        
-        print("Processed manual control command:", response_data)
-        return "cmd_vel", response_data
-
-    def handle_request_map(self, client_socket, _):
-            """Handles the REQMAP command."""
-            # Relative path to the JSON file
-            graph_file_path = os.path.join("src", "robobin", "robobin", "graphs", "graph.json")
-
-            try:
-                # Load the graph JSON file
-                with open(graph_file_path, 'r') as f:
-                    graph_data = json.load(f)
-
-                # Serialize the JSON data to a string
-                graph_json = json.dumps(graph_data)
-                # Send the JSON response back to the client
-                if self.testing:
-                    print("Sending map data:", graph_json)
-                else:
-                    client_socket.sendall(graph_json.encode())
-
-                return None
-
-            except FileNotFoundError:
-                error_message = f"Error: File not found at {graph_file_path}"
-                if self.testing:
-                    print(error_message)
-                else:
-                    client_socket.sendall(error_message.encode())
-
-                return None
-
-            except json.JSONDecodeError as e:
-                error_message = f"Error: Failed to decode JSON - {str(e)}"
-                if self.testing:
-                    print(error_message)
-                else:
-                    client_socket.sendall(error_message.encode())
-
-                return None
-
-            except Exception as e:
-                error_message = f"Error: {str(e)}"
-                if self.testing:
-                    print(error_message)
-                else:
-                    client_socket.sendall(error_message.encode())
-
-                return None
-    def handle_unknown_message(self, client_socket, _):
-        """Handles unknown commands."""
-        response = b"Unknown command"
-        if self.testing:
-            print(response.decode())
-        else:
-            client_socket.sendall(response)
-        return None
-    
-# Test class without api_node and with testing enabled
-if __name__ == "__main__":
-    message_handler = MessageHandler(None, testing=True)
-    assert message_handler.handle_message(None, "PING") is None
-    assert message_handler.handle_message(None, "TIME") is None
-    assert message_handler.handle_message(None, "MANUALCTRL W") == ("cmd_vel", (0.5, 0))
-    assert message_handler.handle_message(None, "MANUALCTRL A") == ("cmd_vel", (0, 0.5))
-    assert message_handler.handle_message(None, "MANUALCTRL S") == ("cmd_vel", (-0.5, 0))
-    assert message_handler.handle_message(None, "MANUALCTRL D") == ("cmd_vel", (0, -0.5))
-
-    assert message_handler.handle_message(None, "STOP") == ("cmd_vel", (0.0, 0.0))
-    assert message_handler.handle_message(None, "CALLME (212.9638, 283.98108)") == ("nav_command", "(212.9638, 283.98108)")
-    assert message_handler.handle_message(None, "UNKNOWN") is None
-    assert message_handler.handle_message(None, "REQMAP") is None
\ No newline at end of file
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py
deleted file mode 100644
index a314cec3db27597e1303cf8ca2d0a00523600dbe..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py
+++ /dev/null
@@ -1,263 +0,0 @@
-import time
-import numpy as np
-import serial
-from scipy.optimize import least_squares
-
-# Define test values at the top of the file for easy modification
-TEST_MEASURED_DISTANCES = [302, 463, 286, 304, 418, 328]
-TEST_TAG1_DISTANCES = [22, 107, 246, 295]
-TEST_TAG2_DISTANCES = [100, 100, 100, 100]
-
-class SerialBuffer:
-    def __init__(self, port):
-        self.ser = serial.Serial(port, 115200, timeout=1)
-
-    def readFromDevice(self, expectedLines=1):
-        lines = []
-        # Attempt to read expected lines; if device is slow, you may need retries
-        while len(lines) < expectedLines:
-            if self.ser.in_waiting:
-                line = self.ser.readline().decode().strip()
-                if line:
-                    lines.append(line)
-            else:
-                time.sleep(0.01)
-        return lines
-
-    def getBeaconPositioningDistances(self):
-        """Reads the measured distances (A,E,D,B,F,C) from the device."""
-        self.writeToDevice("bpm")
-        buffer = self.readFromDevice(1)[0]
-        values = list(map(float, buffer.split(" ")))
-        return values
-
-    def getRangingDistances(self):
-        """Reads the distances from the tags to the anchors."""
-        self.writeToDevice("rng")
-        lines = self.readFromDevice(2)
-        print(lines)
-        distances = []
-        # First line: Tag 1 distances
-        distances.append(list(map(float, lines[0][1:].split(" "))))
-        # Second line: Tag 2 distances or "0"
-        if lines[1] != "1":
-            distances.append(list(map(float, lines[1][1:].split(" "))))
-        else:
-            distances.append(None)
-        return distances
-
-    def writeToDevice(self, value):
-        self.ser.write((value + "\n").encode())
-
-    def __del__(self):
-        print("Closing port")
-        self.ser.close()
-
-
-class AnchorTagCLI:
-    def __init__(self, port="/dev/tty.usbmodem14101", testing=False):
-        self.testing = testing
-        self.serial_buffer = SerialBuffer(port)
-
-        # Distances between anchors (A,E,D,B,F,C)
-        # Corresponding to the measured_distances in original code.
-        self.measured_distances = [0.0]*6
-
-        # Distances from Tag 1 to anchors: A1, A2, A3, A4
-        self.tag_distances = {"A1": 0.0, "A2": 0.0, "A3": 0.0, "A4": 0.0}
-
-        # Distances from Tag 2 to anchors: A1, A2, A3, A4
-        self.tag2_distances = {"A1": 0.0, "A2": 0.0, "A3": 0.0, "A4": 0.0}
-
-        self.anchors = {}
-        self.anchors_coords_known = False
-
-        if self.testing:
-            # Set predefined test distances
-            for i, dist in enumerate(TEST_MEASURED_DISTANCES):
-                self.measured_distances[i] = dist
-
-            for (anchor, dist) in zip(self.tag_distances.keys(), TEST_TAG1_DISTANCES):
-                self.tag_distances[anchor] = dist
-
-            for (anchor, dist) in zip(self.tag2_distances.keys(), TEST_TAG2_DISTANCES):
-                self.tag2_distances[anchor] = dist
-
-    def determine_anchor_coords(self):
-        try:
-            measured_distances = np.array(self.measured_distances)
-            noise_level = 0.0
-            measured_distances_noisy = measured_distances + np.random.uniform(-noise_level, noise_level, size=len(measured_distances))
-
-            # Variables: x_B, y_B, x_C, y_C, y_A
-            initial_guess = [120, 100, 150, 200, 50] # [x_B, y_B, x_C, y_C, y_A]
-            maxBounds = 30000
-            bounds = ([0, 0, 0, 0, 0], [maxBounds] * 5)
-
-            def error_function(variables, measured):
-                x_B, y_B, x_C, y_C, y_A = variables
-                # measured: [A, E, D, B, F, C]
-                a_measured = measured[0]
-                e_measured = measured[1]
-                d_measured = measured[2]
-                b_measured = measured[3]
-                f_measured = measured[4]
-                c_measured = measured[5]
-
-                # A=(0,y_A), B=(x_B,y_B), C=(x_C,y_C), D=(0,0)
-                a_calc = np.sqrt((x_B - 0)**2 + (y_B - y_A)**2)  # A-B
-                b_calc = np.sqrt((x_C - x_B)**2 + (y_C - y_B)**2) # B-C
-                c_calc = np.sqrt(x_C**2 + y_C**2)                 # C-D
-                d_calc = y_A                                      # A-D
-                e_calc = np.sqrt(x_C**2 + (y_C - y_A)**2)         # A-C
-                f_calc = np.sqrt(x_B**2 + y_B**2)                 # B-D
-
-                return [
-                    a_calc - a_measured,
-                    b_calc - b_measured,
-                    c_calc - c_measured,
-                    d_calc - d_measured,
-                    e_calc - e_measured,
-                    f_calc - f_measured
-                ]
-
-            # Run least squares optimization
-            result_noisy = least_squares(
-                error_function,
-                initial_guess,
-                args=(measured_distances_noisy,),
-                bounds=bounds,
-                loss='soft_l1'
-            )
-            optimized_coords_noisy = result_noisy.x
-
-            self.anchors = {
-                "A1": (0, optimized_coords_noisy[4]),
-                "A2": (optimized_coords_noisy[0], optimized_coords_noisy[1]),
-                "A3": (optimized_coords_noisy[2], optimized_coords_noisy[3]),
-                "A4": (0, 0),
-            }
-            return {k: (round(v[0], 2), round(v[1], 2)) for k, v in self.anchors.items()}
-        except Exception as e:
-            print(f"Error generating anchors: {e}")
-
-    def calculate_tag_coordinates(self, tag_distances):
-        if not self.anchors_coords_known or len(self.anchors) < 3:
-            return None, None
-     
-        available_beacons = []
-        available_distances = []
-        for key in tag_distances.keys():
-            d = max(float(tag_distances[key]), 0)
-            available_distances.append(d)
-            available_beacons.append(self.anchors[key])
-
-        if len(available_beacons) < 3:
-            return None, None
-
-        def error_function(vars):
-            x, y = vars
-            residuals = []
-            for (bx, by), d_measured in zip(available_beacons, available_distances):
-                d_computed = np.sqrt((x - bx)**2 + (y - by)**2)
-                residuals.append(d_computed - d_measured)
-            return residuals
-
-        beacon_xs = [b[0] for b in available_beacons]
-        beacon_ys = [b[1] for b in available_beacons]
-        initial_guess = [np.mean(beacon_xs), np.mean(beacon_ys)]
-
-        x_min = min(beacon_xs) - 100
-        x_max = max(beacon_xs) + 100
-        y_min = min(beacon_ys) - 100
-        y_max = max(beacon_ys) + 100
-        bounds = ([x_min, y_min], [x_max, y_max])
-
-        result = least_squares(error_function, initial_guess, bounds=bounds, loss='soft_l1')
-        x_tag, y_tag = result.x
-        return x_tag, y_tag
-
-    def call_bpm(self):
-        if self.testing:
-            beacon_distances = TEST_MEASURED_DISTANCES
-        else:
-            beacon_distances = self.serial_buffer.getBeaconPositioningDistances()
-
-        for i, distance in enumerate(beacon_distances):
-            if i < len(self.measured_distances):
-                self.measured_distances[i] = distance
-
-        determined_anchor_coords = self.determine_anchor_coords()
-        if determined_anchor_coords:
-            self.anchors_coords_known = True
-            print("Anchor coordinates determined:")
-            for anchor, coords in determined_anchor_coords.items():
-                print(f"{anchor}: {coords}")
-
-    def update_distances_and_calculate_tags(self):
-        if not self.anchors_coords_known:
-            return
-
-        if self.testing:
-            ranging_distances = [TEST_TAG1_DISTANCES, TEST_TAG2_DISTANCES]
-        else:
-            ranging_distances = self.serial_buffer.getRangingDistances()
-
-        # Update tag 1 distances
-        if ranging_distances[0] is not None:
-            for i, distance in enumerate(ranging_distances[0]):
-                anchor = list(self.tag_distances.keys())[i]
-                self.tag_distances[anchor] = distance
-
-        # Update tag 2 distances
-        if ranging_distances[1] is not None:
-            for i, distance in enumerate(ranging_distances[1]):
-                anchor = list(self.tag2_distances.keys())[i]
-                self.tag2_distances[anchor] = distance
-
-        # Now calculate both tags
-        tag1_x, tag1_y = self.calculate_tag_coordinates(self.tag_distances)
-        valid_tag2_distances = [dist for dist in self.tag2_distances.values() if dist > 0]
-
-        # Check if there are enough valid distances for Tag 2
-        if len(valid_tag2_distances) < 3:
-            print(f"Insufficient valid distances for Tag 2: {len(valid_tag2_distances)} provided.")
-            tag2_x, tag2_y = None, None
-        else:
-            tag2_x, tag2_y = self.calculate_tag_coordinates(self.tag2_distances)
-
-        print("Tag Positions:")
-        if tag1_x is not None and tag1_y is not None:
-            print(f"Tag 1: ({tag1_x:.2f}, {tag1_y:.2f})")
-        else:
-            print("Tag 1: Not enough data")
-
-        if tag2_x is not None and tag2_y is not None:
-            print(f"Tag 2: ({tag2_x:.2f}, {tag2_y:.2f})")
-        else:
-            print("Tag 2: Not enough data")
-
-      
-        if tag1_x is not None and tag1_y is not None and tag2_x is not None and tag2_y is not None:
-            dx = tag2_x - tag1_x
-            dy = tag2_y - tag1_y
-            displacement = np.sqrt(dx**2 + dy**2)
-            angle_deg = np.degrees(np.arctan2(dy, dx))
-            if angle_deg < 0:
-                angle_deg += 360
-            print(f"Direction from Tag1 to Tag2: dx={dx:.2f}, dy={dy:.2f}, displacement={displacement:.2f}, angle={angle_deg:.2f}°")
-        return tag1_x, tag1_y
-
-if __name__ == "__main__":
-    app = AnchorTagCLI(port="/dev/tty.usbmodem14101", testing=False)
-    while True:
-        user_input = input("Enter command ('bpm' to set anchors, or 'quit' to exit): ").strip().lower()
-        if user_input == "bpm":
-            app.call_bpm()
-            print("Switching to continuous ranging updates (simulating 'rng' messages)...")
-            while True:
-                app.update_distances_and_calculate_tags()
-                time.sleep(1)
-        elif user_input == "quit":
-            print("Exiting program.")
-            break
\ No newline at end of file
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py
deleted file mode 100644
index d20c2dad0c8ab6525395a00d74ce5833f1fa2d94..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py
+++ /dev/null
@@ -1,95 +0,0 @@
-#!/usr/bin/env python3
-
-import rclpy
-from rclpy.node import Node
-from sensor_msgs.msg import Imu
-from smbus2 import SMBus
-import time
-import math
-
-class BNO055Publisher(Node):
-    def __init__(self):
-        super().__init__('imu_node')
-        self.publisher_ = self.create_publisher(Imu, 'imu', 10)
-        self.timer = self.create_timer(0.1, self.timer_callback)
-        self.bus = SMBus(1)
-        self.address = 0x28
-        self.init_bno055()
-        time.sleep(1)
-
-    def write_register(self, register, value):
-        self.bus.write_byte_data(self.address, register, value)
-
-    def read_register(self, register, length=1):
-        if length == 1:
-            return self.bus.read_byte_data(self.address, register)
-        else:
-            return self.bus.read_i2c_block_data(self.address, register, length)
-
-    def init_bno055(self):
-        # Switch to CONFIG mode
-        self.write_register(0x3D, 0x00)
-        time.sleep(0.05)
-        # Set power mode to Normal
-        self.write_register(0x3E, 0x00)
-        # Set to NDOF mode
-        self.write_register(0x3D, 0x0C)
-        time.sleep(0.5)
-
-    def read_euler_angles(self):
-        data = self.read_register(0x1A, 6)
-        yaw = (data[1] << 8) | data[0]
-        roll = (data[3] << 8) | data[2]
-        pitch = (data[5] << 8) | data[4]
-        yaw = yaw if yaw < 32768 else yaw - 65536
-        roll = roll if roll < 32768 else roll - 65536
-        pitch = pitch if pitch < 32768 else pitch - 65536
-        yaw = yaw / 16.0
-        roll = roll / 16.0
-        pitch = pitch / 16.0
-        return yaw, pitch, roll
-
-    def timer_callback(self):
-        yaw, pitch, roll = self.read_euler_angles()
-        imu_msg = Imu()
-        imu_msg.header.stamp = self.get_clock().now().to_msg()
-        imu_msg.header.frame_id = 'imu_link'
-        # Convert degrees to radians
-        yaw_rad = -(math.radians(yaw))
-        roll_rad = -(math.radians(pitch))
-        pitch_rad = -(math.radians(roll))
-        # Compute quaternion
-        cy = math.cos(yaw_rad * 0.5)
-        sy = math.sin(yaw_rad * 0.5)
-        cp = math.cos(pitch_rad * 0.5)
-        sp = math.sin(pitch_rad * 0.5)
-        cr = math.cos(roll_rad * 0.5)
-        sr = math.sin(roll_rad * 0.5)
-        imu_msg.orientation.w = cr * cp * cy + sr * sp * sy
-        imu_msg.orientation.x = sr * cp * cy - cr * sp * sy
-        imu_msg.orientation.y = cr * sp * cy + sr * cp * sy
-        imu_msg.orientation.z = cr * cp * sy - sr * sp * cy
-
-        imu_msg.orientation_covariance = [0.0025, 0, 0,
-                                  0, 0.0025, 0,
-                                  0, 0, 0.0025]
-        imu_msg.angular_velocity_covariance = [0.02, 0, 0,
-                                            0, 0.02, 0,
-                                            0, 0, 0.02]
-        imu_msg.linear_acceleration_covariance = [0.04, 0, 0,
-                                                0, 0.04, 0,
-                                                0, 0, 0.04]
-
-
-        self.publisher_.publish(imu_msg)
-        #self.get_logger().info(f'Publishing: Yaw={yaw:.2f}, Pitch={pitch:.2f}, Roll={roll:.2f}')
-
-def main(args=None):
-    rclpy.init(args=args)
-    bno055_publisher = BNO055Publisher()
-    rclpy.spin(bno055_publisher)
-    bno055_publisher.destroy_node()
-    rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
\ No newline at end of file
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py
deleted file mode 100644
index 25786c4a14305145926601ce96e723029b42c750..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py
+++ /dev/null
@@ -1,73 +0,0 @@
-#!/usr/bin/env python3
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Twist
-from gpiozero import PWMOutputDevice
-from time import sleep
-
-class Motor:
-    def __init__(self, node, EnaA, In1A, In2A, EnaB, In1B, In2B):
-        self.node = node
-        self.pwmA = PWMOutputDevice(EnaA)
-        self.in1A = PWMOutputDevice(In1A)
-        self.in2A = PWMOutputDevice(In2A)
-        self.pwmB = PWMOutputDevice(EnaB)
-        self.in1B = PWMOutputDevice(In1B)
-        self.in2B = PWMOutputDevice(In2B)
-
-    def move(self, speed=0.0, turn=0.0):
-        speed = max(-1, min(1, speed))
-        turn = max(-1, min(1, turn))
-
-        leftSpeed = speed - turn
-        rightSpeed = speed + turn
-        '''
-        left_speed = self.desired_speed - (turn_rate * self.motor.wheel_base / 2)
-        right_speed = self.desired_speed + (turn_rate * self.motor.wheel_base / 2)
-        '''
-
-        leftSpeed = max(-1, min(1, leftSpeed))
-        rightSpeed = max(-1, min(1, rightSpeed))
-
-        self.pwmA.value = abs(leftSpeed)
-        self.in1A.value = leftSpeed <=  0
-        self.in2A.value = leftSpeed > 0
-
-        self.pwmB.value = abs(rightSpeed)
-        self.in1B.value = rightSpeed > 0
-        self.in2B.value = rightSpeed <= 0
-
-        self.node.get_logger().info(f"Left Motor: Speed={leftSpeed}, Right Motor: Speed={rightSpeed}")
-
-
-    def stop(self):
-        self.pwmA.value = 0
-        self.pwmB.value = 0
-
-class MotorControlNode(Node):
-    def __init__(self):
-        super().__init__('motor_control_node')
-        self.get_logger().info("hello")
-        self.motor = Motor(self, 14, 15, 18, 17, 22, 27)
-        self.subscription = self.create_subscription(
-            Twist,
-            'cmd_vel',
-            self.cmd_vel_callback,
-            10
-        )
-
-    def cmd_vel_callback(self, msg):
-        linear_x = msg.linear.x
-        angular_z = msg.angular.z
-        self.motor.move(speed=linear_x, turn=angular_z)
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = MotorControlNode()
-    rclpy.spin(node)
-    rclpy.shutdown()
-
-if __name__ == '__main__':
-    main()
-
-#colcon build --symlink-install
\ No newline at end of file
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py
deleted file mode 100644
index 64c4d16fdc9953aae6337abffe5aa4ee71bc24dc..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py
+++ /dev/null
@@ -1,316 +0,0 @@
-import json
-import os
-import time
-import numpy as np
-from scipy.optimize import least_squares
-from geometry_msgs.msg import Point
-import rclpy
-from rclpy.node import Node
-from std_msgs.msg import String
-from sensor_msgs.msg import Imu
-import tf_transformations
-
-class SerialBuffer:
-    def __init__(self, port):
-        import serial
-        self.ser = serial.Serial(port, 115200, timeout=1)
-
-    def readFromDevice(self, expectedLines=1):
-        lines = []
-        while len(lines) < expectedLines:
-            if self.ser.in_waiting:
-                line = self.ser.readline().decode().strip()
-                if line:
-                    lines.append(line)
-            else:
-                time.sleep(0.01)
-        return lines
-
-    def getBeaconPositioningDistances(self):
-        # return [302, 463, 286, 304, 418, 328]
-        self.writeToDevice("bpm")
-        buffer = self.readFromDevice(1)[0]
-        values = list(map(float, buffer.split(" ")))
-        
-        return values
-
-    def getRangingDistances(self):
-        
-        self.writeToDevice("rng")
-        lines = self.readFromDevice(2)
-
-        print(lines)
-        distances = []
-        distances.append(list(map(float, lines[0][1:].split(" "))))
-        if lines[1] != "1":
-           distances.append(list(map(float, lines[1][1:].split(" "))))
-        else:
-            distances.append(None)
-        return distances
-
-    def writeToDevice(self, value):
-        self.ser.write((value + "\n").encode())
-
-    def __del__(self):
-        self.ser.close()
-
-class UWBNode(Node):
-    def __init__(self):
-        super().__init__('uwb_navigation_node')
-
-        self.publisher = self.create_publisher(Point, '/tag1_location', 10)
-        self.subscription = self.create_subscription(String, '/nav_command', self.handle_nav_command, 10)
-        self.imu_subscription = self.create_subscription(Imu, '/imu', self.handle_imu, 10)
-
-        self.current_yaw = None  # Store the current IMU yaw
-        self.uwb_to_imu_offset = None  # Offset between UWB and IMU heading
-        
-        self.serial_buffer = SerialBuffer("/dev/ttyACM0")
-        self.anchors = {}
-        self.anchors_coords_known = False
-        self.previous_tag1_position = None
-        anchors_file_path = os.path.join("src", "robobin", "robobin", "graphs", "anchors.json")
-        if os.path.exists(anchors_file_path):
-            try:
-                with open(anchors_file_path, 'r') as f:
-                    anchors_data = json.load(f)
-                    self.anchors = anchors_data
-                    self.anchors_coords_known = True
-                    self.get_logger().info("Anchor coordinates loaded from anchors.json.")
-            except Exception as e:
-                self.get_logger().error(f"Failed to load anchors.json: {e}")
-                self.anchors_coords_known = False
-        else:
-            self.get_logger().warning("anchors.json not found, anchor coordinates not known.")
-            self.anchors_coords_known = False
-
-        # Timer to continuously fetch and publish positions
-        self.timer = self.create_timer(1.0, self.update_positions)
-
-    def call_bpm(self):
-        try:
-            beacon_distances = self.serial_buffer.getBeaconPositioningDistances()
-            self.get_logger().info(f"Retreived values {beacon_distances }")
-            self.determine_anchor_coords(beacon_distances)
-            self.anchors_coords_known = True
-            self.get_logger().info("Anchor coordinates determined.")
-            anchors_file_path = os.path.join("src", "robobin", "robobin", "graphs", "anchors.json")
-            try:
-                with open(anchors_file_path, 'w') as f:
-                    json.dump(self.anchors, f)
-                self.get_logger().info("Anchor coordinates saved to anchors.json.")
-
-
-                graph = {
-                    "name": "Lab 1 Extended",
-                    "nodes": [],
-                    "connections": []
-                }
-
-                # Populate nodes with anchor data
-                anchor_names = ["A1", "A2", "A3", "A4"]
-                for i, (key, coords) in enumerate(self.anchors.items()):
-                    graph["nodes"].append({"name": anchor_names[i], "x": coords[0], "y": coords[1]})
-
-                # Create a fully connected adjacency matrix (all nodes connected)
-                num_nodes = len(graph["nodes"])
-                graph["connections"] = [[True if i != j else False for j in range(num_nodes)] for i in range(num_nodes)]
-
-                # Save graph to file
-                graph_file_path = os.path.join("src", "robobin", "robobin", "graphs", "graph.json")
-                with open(graph_file_path, 'w') as f:
-                    json.dump(graph, f, indent=2)
-                self.get_logger().info("Graph saved to graph.json.")
-
-       
-            except Exception as e:
-                self.get_logger().error(f"Failed to save anchors.json: {e}")
-
-        except Exception as e:
-            self.get_logger().error(f"Failed to determine anchors: {e}")
-
-    def handle_imu(self, msg):
-        # Extract yaw from quaternion
-        orientation_q = msg.orientation
-        orientation_list = [orientation_q.x, orientation_q.y, orientation_q.z, orientation_q.w]
-        _, _, yaw = tf_transformations.euler_from_quaternion(orientation_list)
-        
-        self.current_yaw = yaw  # Update current yaw
-        self.get_logger().info(f"IMU Yaw: {yaw:.2f} radians")
-    def determine_anchor_coords(self, measured_distances):
-        measured_distances = np.array(measured_distances)
-
-        initial_guess = [120, 100, 150, 200, 50]
-        bounds = ([0, 0, 0, 0, 0], [1000, 1000, 1000, 1000, 1000])
-
-        def error_function(variables, measured):
-            x_B, y_B, x_C, y_C, y_A = variables
-            a_calc = np.sqrt((x_B - 0)**2 + (y_B - y_A)**2)  # A-B
-            b_calc = np.sqrt((x_C - x_B)**2 + (y_C - y_B)**2)  # B-C
-            c_calc = np.sqrt(x_C**2 + y_C**2)  # C-D
-            d_calc = y_A  # A-D
-            e_calc = np.sqrt(x_C**2 + (y_C - y_A)**2)  # A-C
-            f_calc = np.sqrt(x_B**2 + y_B**2)  # B-D
-
-            return [
-                a_calc - measured[0],
-                b_calc - measured[3],
-                c_calc - measured[5],
-                d_calc - measured[2],
-                e_calc - measured[1],
-                f_calc - measured[4]
-            ]
-
-        result = least_squares(
-            error_function,
-            initial_guess,
-            args=(measured_distances,),
-            bounds=bounds,
-            loss='soft_l1'
-        )
-        x_B, y_B, x_C, y_C, y_A = result.x
-        self.anchors = {
-            "A1": (0, y_A),
-            "A2": (x_B, y_B),
-            "A3": (x_C, y_C),
-            "A4": (0, 0)
-        }
-
-    def calculate_tag_coordinates(self, tag_distances):
-        # self.get_logger().info(f"Tag distances: {tag_distances}")
-        if not self.anchors_coords_known or len(self.anchors) < 3:
-            self.get_logger().warning("Anchor coordinates not known.")
-            return None
-        
-        available_beacons = []
-        available_distances = []
-
-        for key, dist in tag_distances.items():
-            if dist > 0:
-                available_distances.append(dist)
-                available_beacons.append(self.anchors[key])
-
-        if len(available_beacons) < 3:
-            return None
-
-        def error_function(vars):
-            x, y = vars
-            residuals = []
-            for (bx, by), d_measured in zip(available_beacons, available_distances):
-                d_computed = np.sqrt((x - bx)**2 + (y - by)**2)
-                residuals.append(d_computed - d_measured)
-            return residuals
-
-        beacon_xs = [b[0] for b in available_beacons]
-        beacon_ys = [b[1] for b in available_beacons]
-        initial_guess = [np.mean(beacon_xs), np.mean(beacon_ys)]
-
-        bounds = (
-            [min(beacon_xs) - 100, min(beacon_ys) - 100],
-            [max(beacon_xs) + 100, max(beacon_ys) + 100]
-        )
-
-        result = least_squares(error_function, initial_guess, bounds=bounds, loss='soft_l1')
-        self.get_logger().info(f"Optimization result: {result.x}")
-        return tuple(result.x)
-
-    def update_positions(self):
-        self.get_logger().info("Updating positions...")
-        #self.get_logger().info(f"Is anchor coords known: {self.anchors_coords_known}")
-        if self.anchors_coords_known:
-            
-            
-
-            try:
-                ranging_distances = self.serial_buffer.getRangingDistances()
-                self.get_logger().info(f"Ranging Distances {ranging_distances}")
-                tag1_distances = ranging_distances[0]
-                self.get_logger().info(f"Tag1 distances {tag1_distances}")
-                tag_distances_dict = {
-                    "A1": tag1_distances[0],
-                    "A2": tag1_distances[1],
-                    "A3": tag1_distances[2],
-                    "A4": tag1_distances[3]
-                }
-                self.get_logger().info(f"Tag distances: {tag_distances_dict}")
-                tag1_position = self.calculate_tag_coordinates(tag_distances_dict)
-
-                if tag1_position is not None :
-                    self.previous_tag1_position = tag1_position
-                    position_msg = Point(x=tag1_position[0], y=tag1_position[1], z=0.0)
-                    self.publisher.publish(position_msg)
-                    #self.get_logger().info(f"Published new Tag 1 position: {tag1_position}")
-
-                #self.get_logger().info(f"Tag 1 position: {tag1_position}")
-                tag2_distances = ranging_distances[1]
-                self.get_logger().info(f"Tag2 distances {tag2_distances}")
-                tag2_position = None
-                if tag2_distances is not None:
-                    
-                    tag2_distances_dict = {
-                        "A1": tag2_distances[0],
-                        "A2": tag2_distances[1],
-                        "A3": tag2_distances[2],
-                        "A4": tag2_distances[3]
-                    }
-                    tag2_position = self.calculate_tag_coordinates(tag2_distances_dict)
-                else:
-                    self.get_logger().warning("Tag 2 is not known")
-      
-
-                # Calculate angle between tag1 and tag2, then print out the angle. @TODO: Move the bin forward to see which direction we are facing, then match the angle with the IMU yaw. This will then mean we can calculate the offset between the UWB and IMU heading.
-                if tag2_position is not None:
-                    displacement_x = tag2_position[0] - tag1_position[0]
-                    displacement_y = tag2_position[1] - tag1_position[1]
-                    
-                    # Calculate angle and distance
-                    displacement_angle = np.arctan2(displacement_y, displacement_x)  
-                    displacement_distance = np.sqrt(displacement_x**2 + displacement_y**2)
-                    
-                    self.get_logger().info(f"Displacement: dx={displacement_x:.2f}, dy={displacement_y:.2f}")
-                    self.get_logger().info(f"Displacement Angle: {np.degrees(displacement_angle):.2f}°")
-                    self.get_logger().info(f"Displacement Distance: {displacement_distance:.2f} units")
-                
-
-            except Exception as e:
-                self.get_logger().error(f"Error updating positions: {e}")
-    def clear_graph(self):
-        self.anchors_coords_known = False
-        self.anchors = {}
-        self.previous_tag1_position = None
-        graph_file_path = os.path.join("src", "robobin", "robobin", "graphs", "graph.json")
-        default_file_path = os.path.join("src", "robobin", "robobin", "graphs", "default_graph.json")
-        try:
-            with open(default_file_path, 'r') as f:
-                graph_data = json.load(f)
-                with open(graph_file_path, 'w') as f:
-                    json.dump(graph_data, f)
-        except FileNotFoundError:
-            self.get_logger().error(f"Error: File not found at {default_file_path}")
-        except json.JSONDecodeError as e:
-            self.get_logger().error(f"Error: Failed to decode JSON - {str(e)}")
-        except Exception as e:
-            self.get_logger().error(f"Error: {str(e)}")
-
-        self.get_logger().info("Graph cleared.")
-
-
-    def handle_nav_command(self, msg):
-        if msg.data == "BPM":
-            self.clear_graph()
-            self.call_bpm()
-            self.anchors_coords_known = True
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = UWBNode()
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-if __name__ == "__main__":
-    main()
diff --git a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py b/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py
deleted file mode 100644
index dec8b95597d81d37e8cc8f3d74aef15b9c7702c8..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py
+++ /dev/null
@@ -1,122 +0,0 @@
-import rclpy
-from rclpy.node import Node
-from geometry_msgs.msg import Twist, Point
-from math import sqrt, pow, atan2, radians, sin, cos
-import time
-
-
-class UWBPathingNode(Node):
-    def __init__(self):
-        super().__init__('uwb_pathing_node')
-
-        # Publisher for cmd_vel
-        self.cmd_vel_pub = self.create_publisher(Twist, '/cmd_vel', 10)
-
-        # Subscriptions
-        self.create_subscription(Point, '/start_location', self.current_location_callback, 10)
-        self.create_subscription(Point, '/target_location', self.target_location_callback, 10)
-
-        # Current and target positions
-        self.current_x = None
-        self.current_y = None
-        self.target_x = None
-        self.target_y = None
-
-        # Navigation thresholds
-        self.distance_threshold = 0.25  # meters
-        self.angle_threshold = radians(0.5)  # radians
-
-        self.kp_linear = 0.5  # Proportional gain for linear movement
-        self.kp_angular = 1.0  # Proportional gain for angular movement
-
-        self.get_logger().info('UWB Pathing Node started and waiting for positions.')
-
-    def current_location_callback(self, msg: Point):
-        """Callback to update the robot's current position."""
-        self.current_x = msg.x
-        self.current_y = msg.y
-        self.get_logger().info(f"Current Location Updated: x={self.current_x:.2f}, y={self.current_y:.2f}")
-        self.check_and_navigate()
-
-    def target_location_callback(self, msg: Point):
-        """Callback to update the target position."""
-        self.target_x = msg.x
-        self.target_y = msg.y
-        self.get_logger().info(f"Target Location Updated: x={self.target_x:.2f}, y={self.target_y:.2f}")
-        self.check_and_navigate()
-
-    def check_and_navigate(self):
-        """Check if both positions are available and navigate to the target."""
-        if self.current_x is not None and self.current_y is not None and self.target_x is not None and self.target_y is not None:
-            self.get_logger().info("Navigating to target...")
-            self.navigate_to_target()
-        else:
-            self.get_logger().warning("Waiting for both current and target positions to be available...")
-
-    def navigate_to_target(self):
-        # Ensure positions are known
-        if self.current_x is None or self.current_y is None or self.target_x is None or self.target_y is None:
-            self.get_logger().warning("Positions not fully known yet.")
-            return
-
-        # Calculate distance and angle to the target
-        displacement_x = self.target_x - self.current_x
-        displacement_y = self.target_y - self.current_y
-        distance_to_target = sqrt(pow(displacement_x, 2) + pow(displacement_y, 2))
-        angle_to_target = atan2(displacement_y, displacement_x)
-
-
-        # Check if we are close enough to the target
-        if distance_to_target <= self.distance_threshold:
-            self.stop_robot()
-            self.get_logger().info("Target reached successfully.")
-            return
-
-        # Calculate yaw error (assuming robot orientation 0 = facing x-axis)
-        # If you don't have actual orientation, you might assume the robot always faces the target directly
-        yaw_error = angle_to_target
-        yaw_error = atan2(sin(yaw_error), cos(yaw_error))  # Normalize angle
-        self.get_logger().info(f"Current Position: x={self.current_x:.2f}, y={self.current_y:.2f}")
-        self.get_logger().info(f"Target Position: x={self.target_x:.2f}, y={self.target_y:.2f}")
-        self.get_logger().info(f"Distance to Target: distance_to_target={distance_to_target:.2f} meters")
-        self.get_logger().info(f"Angle to Target: angle_to_target={angle_to_target:.2f} radians")
-        twist = Twist()
-
-        # Decide on angular velocity first
-        if abs(yaw_error) > self.angle_threshold:
-            angular_speed = self.kp_angular * abs(yaw_error)
-            twist.angular.z = angular_speed if yaw_error > 0 else -angular_speed
-            self.get_logger().info(f"Correcting Heading: yaw_error={yaw_error:.2f} radians")
-        else:
-            # Move forward when aligned with the target
-            linear_speed = self.kp_linear * distance_to_target
-            twist.linear.x = min(0.2, linear_speed)  # Limit max speed
-            self.get_logger().info(f"Moving to Target: distance={distance_to_target:.2f} meters")
-
-        # # Publish movement command
-        # self.cmd_vel_pub.publish(twist)
-
-
-    def stop_robot(self):
-        """Stops the robot by publishing zero velocities."""
-        twist = Twist()
-        self.cmd_vel_pub.publish(twist)
-        time.sleep(0.5)
-        self.get_logger().info("Robot stopped.")
-
-
-def main(args=None):
-    rclpy.init(args=args)
-    node = UWBPathingNode()
-
-    try:
-        rclpy.spin(node)
-    except KeyboardInterrupt:
-        pass
-    finally:
-        node.destroy_node()
-        rclpy.shutdown()
-
-
-if __name__ == '__main__':
-    main()
diff --git a/ros2/src/install/robobin/lib/robobin/api_node b/ros2/src/install/robobin/lib/robobin/api_node
deleted file mode 100755
index cc9aa893d2ea34ec9802860d33c3ecbc56f32a66..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/robobin/api_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','api_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'api_node')())
diff --git a/ros2/src/install/robobin/lib/robobin/control_feedback b/ros2/src/install/robobin/lib/robobin/control_feedback
deleted file mode 100755
index fda03c810291522627cacd9263254ea54c5705b5..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/robobin/control_feedback
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','control_feedback'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'control_feedback')())
diff --git a/ros2/src/install/robobin/lib/robobin/encoder_node b/ros2/src/install/robobin/lib/robobin/encoder_node
deleted file mode 100755
index 306c64070042eb370951600e68701d23352722b4..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/robobin/encoder_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','encoder_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'encoder_node')())
diff --git a/ros2/src/install/robobin/lib/robobin/imu_node b/ros2/src/install/robobin/lib/robobin/imu_node
deleted file mode 100755
index ba00b16aab896a2cdb713ee4fc9fc13897dad633..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/robobin/imu_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','imu_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'imu_node')())
diff --git a/ros2/src/install/robobin/lib/robobin/motor_control_node b/ros2/src/install/robobin/lib/robobin/motor_control_node
deleted file mode 100755
index 42f4d86bd72336858400a8581eaf43f0276200ab..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/robobin/motor_control_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','motor_control_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'motor_control_node')())
diff --git a/ros2/src/install/robobin/lib/robobin/motor_node b/ros2/src/install/robobin/lib/robobin/motor_node
deleted file mode 100755
index 0fbb76f54aae5725259f9f5982e9bea57211b1b9..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/robobin/motor_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','motor_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'motor_node')())
diff --git a/ros2/src/install/robobin/lib/robobin/uwb_navigation_node b/ros2/src/install/robobin/lib/robobin/uwb_navigation_node
deleted file mode 100755
index b69e2c6fd1086e7abef952dd4c84419a5ab010a7..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/robobin/uwb_navigation_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','uwb_navigation_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'uwb_navigation_node')())
diff --git a/ros2/src/install/robobin/lib/robobin/uwb_pathing_node b/ros2/src/install/robobin/lib/robobin/uwb_pathing_node
deleted file mode 100755
index 30066a0eee11b663b598252f6bd63810022ace28..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/lib/robobin/uwb_pathing_node
+++ /dev/null
@@ -1,33 +0,0 @@
-#!/usr/bin/python3
-# EASY-INSTALL-ENTRY-SCRIPT: 'robobin==0.0.0','console_scripts','uwb_pathing_node'
-import re
-import sys
-
-# for compatibility with easy_install; see #2198
-__requires__ = 'robobin==0.0.0'
-
-try:
-    from importlib.metadata import distribution
-except ImportError:
-    try:
-        from importlib_metadata import distribution
-    except ImportError:
-        from pkg_resources import load_entry_point
-
-
-def importlib_load_entry_point(spec, group, name):
-    dist_name, _, _ = spec.partition('==')
-    matches = (
-        entry_point
-        for entry_point in distribution(dist_name).entry_points
-        if entry_point.group == group and entry_point.name == name
-    )
-    return next(matches).load()
-
-
-globals().setdefault('load_entry_point', importlib_load_entry_point)
-
-
-if __name__ == '__main__':
-    sys.argv[0] = re.sub(r'(-script\.pyw?|\.exe)?$', '', sys.argv[0])
-    sys.exit(load_entry_point('robobin==0.0.0', 'console_scripts', 'uwb_pathing_node')())
diff --git a/ros2/src/install/robobin/share/ament_index/resource_index/packages/robobin b/ros2/src/install/robobin/share/ament_index/resource_index/packages/robobin
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/install/robobin/share/colcon-core/packages/robobin b/ros2/src/install/robobin/share/colcon-core/packages/robobin
deleted file mode 100644
index de58d893877c68ce26089692eb0b331a8f7cca35..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/colcon-core/packages/robobin
+++ /dev/null
@@ -1 +0,0 @@
-rclpy:std_msgs
\ No newline at end of file
diff --git a/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.dsv b/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.dsv
deleted file mode 100644
index 79d4c95b55cb72a17c9be498c3758478e2c7bb8d..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.dsv
+++ /dev/null
@@ -1 +0,0 @@
-prepend-non-duplicate;AMENT_PREFIX_PATH;
diff --git a/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.ps1 b/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.ps1
deleted file mode 100644
index 26b99975794bb42ea3d6a17150e313cbfc45fc24..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.ps1
+++ /dev/null
@@ -1,3 +0,0 @@
-# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em
-
-colcon_prepend_unique_value AMENT_PREFIX_PATH "$env:COLCON_CURRENT_PREFIX"
diff --git a/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.sh b/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.sh
deleted file mode 100644
index f3041f688a623ea5c66e65c917bc503e5fae6dc9..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.sh
+++ /dev/null
@@ -1,3 +0,0 @@
-# generated from colcon_core/shell/template/hook_prepend_value.sh.em
-
-_colcon_prepend_unique_value AMENT_PREFIX_PATH "$COLCON_CURRENT_PREFIX"
diff --git a/ros2/src/install/robobin/share/robobin/hook/pythonpath.dsv b/ros2/src/install/robobin/share/robobin/hook/pythonpath.dsv
deleted file mode 100644
index c2ddcdb73d1e5f7457cdbba9133f2e8a4d250b78..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/hook/pythonpath.dsv
+++ /dev/null
@@ -1 +0,0 @@
-prepend-non-duplicate;PYTHONPATH;lib/python3.12/site-packages
diff --git a/ros2/src/install/robobin/share/robobin/hook/pythonpath.ps1 b/ros2/src/install/robobin/share/robobin/hook/pythonpath.ps1
deleted file mode 100644
index bdd69aff5ed6df188b6c51f1b7f3f79e7344a2a8..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/hook/pythonpath.ps1
+++ /dev/null
@@ -1,3 +0,0 @@
-# generated from colcon_powershell/shell/template/hook_prepend_value.ps1.em
-
-colcon_prepend_unique_value PYTHONPATH "$env:COLCON_CURRENT_PREFIX\lib/python3.12/site-packages"
diff --git a/ros2/src/install/robobin/share/robobin/hook/pythonpath.sh b/ros2/src/install/robobin/share/robobin/hook/pythonpath.sh
deleted file mode 100644
index 45388fea975bdbfb649447f4a82b390f9c4b7920..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/hook/pythonpath.sh
+++ /dev/null
@@ -1,3 +0,0 @@
-# generated from colcon_core/shell/template/hook_prepend_value.sh.em
-
-_colcon_prepend_unique_value PYTHONPATH "$COLCON_CURRENT_PREFIX/lib/python3.12/site-packages"
diff --git a/ros2/src/install/robobin/share/robobin/launch/__pycache__/robobin_launch.cpython-312.pyc b/ros2/src/install/robobin/share/robobin/launch/__pycache__/robobin_launch.cpython-312.pyc
deleted file mode 100644
index b2ae9cff8020adaaceb2a578c6ff894f3a33264a..0000000000000000000000000000000000000000
Binary files a/ros2/src/install/robobin/share/robobin/launch/__pycache__/robobin_launch.cpython-312.pyc and /dev/null differ
diff --git a/ros2/src/install/robobin/share/robobin/launch/robobin_launch.py b/ros2/src/install/robobin/share/robobin/launch/robobin_launch.py
deleted file mode 100755
index 25ba08996b53a3ffe92f00e8ab2e9db51b6be1b3..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/launch/robobin_launch.py
+++ /dev/null
@@ -1,32 +0,0 @@
-# ~/GitLab/robobin/ros2/src/robobin/launch/robobin_launch.py
-
-from launch import LaunchDescription
-from launch_ros.actions import Node
-
-def generate_launch_description():
-    return LaunchDescription([
-        Node(
-            package='robobin',
-            executable='api_node',    
-            name='api_node',
-            output='screen',
-            emulate_tty=True
-
-        ),
-       
-        Node(
-            package='robobin',
-            executable='uwb_navigation_node',    
-            name='uwb_navigation_node',
-            output='screen',
-            emulate_tty=True
-        ),
-        # Add additional nodes
-        # Example:
-        # Node(
-        #     package='robobin',
-        #     executable='connection_handler_node',  
-        #     name='connection_handler_node',
-        #     output='screen'
-        # ),
-    ])
diff --git a/ros2/src/install/robobin/share/robobin/launch/robobin_no_components_launch.py b/ros2/src/install/robobin/share/robobin/launch/robobin_no_components_launch.py
deleted file mode 100644
index cea865161157a7774fe733c787e51c92bebf4c1b..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/launch/robobin_no_components_launch.py
+++ /dev/null
@@ -1,31 +0,0 @@
-# ~/GitLab/robobin/ros2/src/robobin/launch/robobin_no_components_launch.py
-
-from launch import LaunchDescription
-from launch_ros.actions import Node
-
-def generate_launch_description():
-    return LaunchDescription([
-        Node(
-            package='robobin',
-            executable='api_node',    
-            name='api_node',
-            output='screen',
-            emulate_tty=True
-
-        ),
-       
-        Node(
-            package='robobin',
-            executable='uwb_navigation_node',    
-            name='uwb_navigation_node',
-            output='screen',
-            emulate_tty=True
-        ),
-        Node(
-            package='robobin',
-            executable='motor_control_node',    
-            name='motor_control_node',
-            output='screen',
-            emulate_tty=True
-        ),
-        ])
\ No newline at end of file
diff --git a/ros2/src/install/robobin/share/robobin/package.bash b/ros2/src/install/robobin/share/robobin/package.bash
deleted file mode 100644
index 06c2f0c093746d83cc96ef961fb7841989fbe95e..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/package.bash
+++ /dev/null
@@ -1,31 +0,0 @@
-# generated from colcon_bash/shell/template/package.bash.em
-
-# This script extends the environment for this package.
-
-# a bash script is able to determine its own path if necessary
-if [ -z "$COLCON_CURRENT_PREFIX" ]; then
-  # the prefix is two levels up from the package specific share directory
-  _colcon_package_bash_COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`/../.." > /dev/null && pwd)"
-else
-  _colcon_package_bash_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
-fi
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-# additional arguments: arguments to the script
-_colcon_package_bash_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$@"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# source sh script of this package
-_colcon_package_bash_source_script "$_colcon_package_bash_COLCON_CURRENT_PREFIX/share/robobin/package.sh"
-
-unset _colcon_package_bash_source_script
-unset _colcon_package_bash_COLCON_CURRENT_PREFIX
diff --git a/ros2/src/install/robobin/share/robobin/package.dsv b/ros2/src/install/robobin/share/robobin/package.dsv
deleted file mode 100644
index acfa8631ecbca19ce01450ed6950bc7ea21d347d..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/package.dsv
+++ /dev/null
@@ -1,6 +0,0 @@
-source;share/robobin/hook/pythonpath.ps1
-source;share/robobin/hook/pythonpath.dsv
-source;share/robobin/hook/pythonpath.sh
-source;share/robobin/hook/ament_prefix_path.ps1
-source;share/robobin/hook/ament_prefix_path.dsv
-source;share/robobin/hook/ament_prefix_path.sh
diff --git a/ros2/src/install/robobin/share/robobin/package.ps1 b/ros2/src/install/robobin/share/robobin/package.ps1
deleted file mode 100644
index 9d07a1c1d35fdeefeac40caf0b7c0e21739c2cfc..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/package.ps1
+++ /dev/null
@@ -1,116 +0,0 @@
-# generated from colcon_powershell/shell/template/package.ps1.em
-
-# function to append a value to a variable
-# which uses colons as separators
-# duplicates as well as leading separators are avoided
-# first argument: the name of the result variable
-# second argument: the value to be prepended
-function colcon_append_unique_value {
-  param (
-    $_listname,
-    $_value
-  )
-
-  # get values from variable
-  if (Test-Path Env:$_listname) {
-    $_values=(Get-Item env:$_listname).Value
-  } else {
-    $_values=""
-  }
-  $_duplicate=""
-  # start with no values
-  $_all_values=""
-  # iterate over existing values in the variable
-  if ($_values) {
-    $_values.Split(";") | ForEach {
-      # not an empty string
-      if ($_) {
-        # not a duplicate of _value
-        if ($_ -eq $_value) {
-          $_duplicate="1"
-        }
-        if ($_all_values) {
-          $_all_values="${_all_values};$_"
-        } else {
-          $_all_values="$_"
-        }
-      }
-    }
-  }
-  # append only non-duplicates
-  if (!$_duplicate) {
-    # avoid leading separator
-    if ($_all_values) {
-      $_all_values="${_all_values};${_value}"
-    } else {
-      $_all_values="${_value}"
-    }
-  }
-
-  # export the updated variable
-  Set-Item env:\$_listname -Value "$_all_values"
-}
-
-# function to prepend a value to a variable
-# which uses colons as separators
-# duplicates as well as trailing separators are avoided
-# first argument: the name of the result variable
-# second argument: the value to be prepended
-function colcon_prepend_unique_value {
-  param (
-    $_listname,
-    $_value
-  )
-
-  # get values from variable
-  if (Test-Path Env:$_listname) {
-    $_values=(Get-Item env:$_listname).Value
-  } else {
-    $_values=""
-  }
-  # start with the new value
-  $_all_values="$_value"
-  # iterate over existing values in the variable
-  if ($_values) {
-    $_values.Split(";") | ForEach {
-      # not an empty string
-      if ($_) {
-        # not a duplicate of _value
-        if ($_ -ne $_value) {
-          # keep non-duplicate values
-          $_all_values="${_all_values};$_"
-        }
-      }
-    }
-  }
-  # export the updated variable
-  Set-Item env:\$_listname -Value "$_all_values"
-}
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-# additional arguments: arguments to the script
-function colcon_package_source_powershell_script {
-  param (
-    $_colcon_package_source_powershell_script
-  )
-  # source script with conditional trace output
-  if (Test-Path $_colcon_package_source_powershell_script) {
-    if ($env:COLCON_TRACE) {
-      echo ". '$_colcon_package_source_powershell_script'"
-    }
-    . "$_colcon_package_source_powershell_script"
-  } else {
-    Write-Error "not found: '$_colcon_package_source_powershell_script'"
-  }
-}
-
-
-# a powershell script is able to determine its own path
-# the prefix is two levels up from the package specific share directory
-$env:COLCON_CURRENT_PREFIX=(Get-Item $PSCommandPath).Directory.Parent.Parent.FullName
-
-colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/robobin/hook/pythonpath.ps1"
-colcon_package_source_powershell_script "$env:COLCON_CURRENT_PREFIX\share/robobin/hook/ament_prefix_path.ps1"
-
-Remove-Item Env:\COLCON_CURRENT_PREFIX
diff --git a/ros2/src/install/robobin/share/robobin/package.sh b/ros2/src/install/robobin/share/robobin/package.sh
deleted file mode 100644
index c95021d5cb7c105222a3fce8008ea05c66265383..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/package.sh
+++ /dev/null
@@ -1,87 +0,0 @@
-# generated from colcon_core/shell/template/package.sh.em
-
-# This script extends the environment for this package.
-
-# function to prepend a value to a variable
-# which uses colons as separators
-# duplicates as well as trailing separators are avoided
-# first argument: the name of the result variable
-# second argument: the value to be prepended
-_colcon_prepend_unique_value() {
-  # arguments
-  _listname="$1"
-  _value="$2"
-
-  # get values from variable
-  eval _values=\"\$$_listname\"
-  # backup the field separator
-  _colcon_prepend_unique_value_IFS=$IFS
-  IFS=":"
-  # start with the new value
-  _all_values="$_value"
-  # workaround SH_WORD_SPLIT not being set in zsh
-  if [ "$(command -v colcon_zsh_convert_to_array)" ]; then
-    colcon_zsh_convert_to_array _values
-  fi
-  # iterate over existing values in the variable
-  for _item in $_values; do
-    # ignore empty strings
-    if [ -z "$_item" ]; then
-      continue
-    fi
-    # ignore duplicates of _value
-    if [ "$_item" = "$_value" ]; then
-      continue
-    fi
-    # keep non-duplicate values
-    _all_values="$_all_values:$_item"
-  done
-  unset _item
-  # restore the field separator
-  IFS=$_colcon_prepend_unique_value_IFS
-  unset _colcon_prepend_unique_value_IFS
-  # export the updated variable
-  eval export $_listname=\"$_all_values\"
-  unset _all_values
-  unset _values
-
-  unset _value
-  unset _listname
-}
-
-# since a plain shell script can't determine its own path when being sourced
-# either use the provided COLCON_CURRENT_PREFIX
-# or fall back to the build time prefix (if it exists)
-_colcon_package_sh_COLCON_CURRENT_PREFIX="/home/robobin/robobin/ros2/src/install/robobin"
-if [ -z "$COLCON_CURRENT_PREFIX" ]; then
-  if [ ! -d "$_colcon_package_sh_COLCON_CURRENT_PREFIX" ]; then
-    echo "The build time path \"$_colcon_package_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2
-    unset _colcon_package_sh_COLCON_CURRENT_PREFIX
-    return 1
-  fi
-  COLCON_CURRENT_PREFIX="$_colcon_package_sh_COLCON_CURRENT_PREFIX"
-fi
-unset _colcon_package_sh_COLCON_CURRENT_PREFIX
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-# additional arguments: arguments to the script
-_colcon_package_sh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$@"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# source sh hooks
-_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/robobin/hook/pythonpath.sh"
-_colcon_package_sh_source_script "$COLCON_CURRENT_PREFIX/share/robobin/hook/ament_prefix_path.sh"
-
-unset _colcon_package_sh_source_script
-unset COLCON_CURRENT_PREFIX
-
-# do not unset _colcon_prepend_unique_value since it might be used by non-primary shell hooks
diff --git a/ros2/src/install/robobin/share/robobin/package.xml b/ros2/src/install/robobin/share/robobin/package.xml
deleted file mode 100644
index fd694d6dfcde24970ee00ec057ad19c1b21a15cc..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/package.xml
+++ /dev/null
@@ -1,21 +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>robobin</name>
-  <version>0.0.0</version>
-  <description>TODO: Package description</description>
-  <maintainer email="plw1g21@soton.ac.uk">paulw</maintainer>
-  <license>TODO: License declaration</license>
-
-  <depend>rclpy</depend>
-  <depend>std_msgs</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/ros2/src/install/robobin/share/robobin/package.zsh b/ros2/src/install/robobin/share/robobin/package.zsh
deleted file mode 100644
index a6a5cc52558a9b09650fee9244a52203c590836d..0000000000000000000000000000000000000000
--- a/ros2/src/install/robobin/share/robobin/package.zsh
+++ /dev/null
@@ -1,42 +0,0 @@
-# generated from colcon_zsh/shell/template/package.zsh.em
-
-# This script extends the environment for this package.
-
-# a zsh script is able to determine its own path if necessary
-if [ -z "$COLCON_CURRENT_PREFIX" ]; then
-  # the prefix is two levels up from the package specific share directory
-  _colcon_package_zsh_COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`/../.." > /dev/null && pwd)"
-else
-  _colcon_package_zsh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
-fi
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-# additional arguments: arguments to the script
-_colcon_package_zsh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$@"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# function to convert array-like strings into arrays
-# to workaround SH_WORD_SPLIT not being set
-colcon_zsh_convert_to_array() {
-  local _listname=$1
-  local _dollar="$"
-  local _split="{="
-  local _to_array="(\"$_dollar$_split$_listname}\")"
-  eval $_listname=$_to_array
-}
-
-# source sh script of this package
-_colcon_package_zsh_source_script "$_colcon_package_zsh_COLCON_CURRENT_PREFIX/share/robobin/package.sh"
-unset convert_zsh_to_array
-
-unset _colcon_package_zsh_source_script
-unset _colcon_package_zsh_COLCON_CURRENT_PREFIX
diff --git a/ros2/src/install/setup.bash b/ros2/src/install/setup.bash
deleted file mode 100644
index 4aeadb4c5f8e80e273a9b473c9a96b3eb7966438..0000000000000000000000000000000000000000
--- a/ros2/src/install/setup.bash
+++ /dev/null
@@ -1,34 +0,0 @@
-# generated from colcon_bash/shell/template/prefix_chain.bash.em
-
-# This script extends the environment with the environment of other prefix
-# paths which were sourced when this file was generated as well as all packages
-# contained in this prefix path.
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-_colcon_prefix_chain_bash_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$1"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# source chained prefixes
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="/opt/ros/jazzy"
-_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="/home/robobin/Robobin_Project/ros2/robobin_main/install"
-_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
-
-# source this prefix
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="$(builtin cd "`dirname "${BASH_SOURCE[0]}"`" > /dev/null && pwd)"
-_colcon_prefix_chain_bash_source_script "$COLCON_CURRENT_PREFIX/local_setup.bash"
-
-unset COLCON_CURRENT_PREFIX
-unset _colcon_prefix_chain_bash_source_script
diff --git a/ros2/src/install/setup.ps1 b/ros2/src/install/setup.ps1
deleted file mode 100644
index 556a86618537b0dd9e6721ace693770497a33081..0000000000000000000000000000000000000000
--- a/ros2/src/install/setup.ps1
+++ /dev/null
@@ -1,30 +0,0 @@
-# generated from colcon_powershell/shell/template/prefix_chain.ps1.em
-
-# This script extends the environment with the environment of other prefix
-# paths which were sourced when this file was generated as well as all packages
-# contained in this prefix path.
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-function _colcon_prefix_chain_powershell_source_script {
-  param (
-    $_colcon_prefix_chain_powershell_source_script_param
-  )
-  # source script with conditional trace output
-  if (Test-Path $_colcon_prefix_chain_powershell_source_script_param) {
-    if ($env:COLCON_TRACE) {
-      echo ". '$_colcon_prefix_chain_powershell_source_script_param'"
-    }
-    . "$_colcon_prefix_chain_powershell_source_script_param"
-  } else {
-    Write-Error "not found: '$_colcon_prefix_chain_powershell_source_script_param'"
-  }
-}
-
-# source chained prefixes
-_colcon_prefix_chain_powershell_source_script "/opt/ros/jazzy\local_setup.ps1"
-_colcon_prefix_chain_powershell_source_script "/home/robobin/Robobin_Project/ros2/robobin_main/install\local_setup.ps1"
-
-# source this prefix
-$env:COLCON_CURRENT_PREFIX=(Split-Path $PSCommandPath -Parent)
-_colcon_prefix_chain_powershell_source_script "$env:COLCON_CURRENT_PREFIX\local_setup.ps1"
diff --git a/ros2/src/install/setup.sh b/ros2/src/install/setup.sh
deleted file mode 100644
index 9a84e67409e3415abc499df23a2ccb4d80538c27..0000000000000000000000000000000000000000
--- a/ros2/src/install/setup.sh
+++ /dev/null
@@ -1,49 +0,0 @@
-# generated from colcon_core/shell/template/prefix_chain.sh.em
-
-# This script extends the environment with the environment of other prefix
-# paths which were sourced when this file was generated as well as all packages
-# contained in this prefix path.
-
-# since a plain shell script can't determine its own path when being sourced
-# either use the provided COLCON_CURRENT_PREFIX
-# or fall back to the build time prefix (if it exists)
-_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX=/home/robobin/robobin/ros2/src/install
-if [ ! -z "$COLCON_CURRENT_PREFIX" ]; then
-  _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX="$COLCON_CURRENT_PREFIX"
-elif [ ! -d "$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX" ]; then
-  echo "The build time path \"$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX\" doesn't exist. Either source a script for a different shell or set the environment variable \"COLCON_CURRENT_PREFIX\" explicitly." 1>&2
-  unset _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX
-  return 1
-fi
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-_colcon_prefix_chain_sh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$1"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# source chained prefixes
-# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
-COLCON_CURRENT_PREFIX="/opt/ros/jazzy"
-_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
-
-# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
-COLCON_CURRENT_PREFIX="/home/robobin/Robobin_Project/ros2/robobin_main/install"
-_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
-
-
-# source this prefix
-# setting COLCON_CURRENT_PREFIX avoids relying on the build time prefix of the sourced script
-COLCON_CURRENT_PREFIX="$_colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX"
-_colcon_prefix_chain_sh_source_script "$COLCON_CURRENT_PREFIX/local_setup.sh"
-
-unset _colcon_prefix_chain_sh_COLCON_CURRENT_PREFIX
-unset _colcon_prefix_chain_sh_source_script
-unset COLCON_CURRENT_PREFIX
diff --git a/ros2/src/install/setup.zsh b/ros2/src/install/setup.zsh
deleted file mode 100644
index 770dee49ec8e02df3085d222804936ad638cad95..0000000000000000000000000000000000000000
--- a/ros2/src/install/setup.zsh
+++ /dev/null
@@ -1,34 +0,0 @@
-# generated from colcon_zsh/shell/template/prefix_chain.zsh.em
-
-# This script extends the environment with the environment of other prefix
-# paths which were sourced when this file was generated as well as all packages
-# contained in this prefix path.
-
-# function to source another script with conditional trace output
-# first argument: the path of the script
-_colcon_prefix_chain_zsh_source_script() {
-  if [ -f "$1" ]; then
-    if [ -n "$COLCON_TRACE" ]; then
-      echo "# . \"$1\""
-    fi
-    . "$1"
-  else
-    echo "not found: \"$1\"" 1>&2
-  fi
-}
-
-# source chained prefixes
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="/opt/ros/jazzy"
-_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="/home/robobin/Robobin_Project/ros2/robobin_main/install"
-_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
-
-# source this prefix
-# setting COLCON_CURRENT_PREFIX avoids determining the prefix in the sourced script
-COLCON_CURRENT_PREFIX="$(builtin cd -q "`dirname "${(%):-%N}"`" > /dev/null && pwd)"
-_colcon_prefix_chain_zsh_source_script "$COLCON_CURRENT_PREFIX/local_setup.zsh"
-
-unset COLCON_CURRENT_PREFIX
-unset _colcon_prefix_chain_zsh_source_script
diff --git a/ros2/src/log/COLCON_IGNORE b/ros2/src/log/COLCON_IGNORE
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/log/build_2024-12-16_14-16-57/events.log b/ros2/src/log/build_2024-12-16_14-16-57/events.log
deleted file mode 100644
index e15f31466855380e44912531ea6ae98ab42cd81d..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_14-16-57/events.log
+++ /dev/null
@@ -1,87 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000385] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000682] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099641] (-) TimerEvent: {}
-[0.200211] (-) TimerEvent: {}
-[0.301520] (-) TimerEvent: {}
-[0.402788] (-) TimerEvent: {}
-[0.505321] (-) TimerEvent: {}
-[0.606327] (-) TimerEvent: {}
-[0.707139] (-) TimerEvent: {}
-[0.808626] (-) TimerEvent: {}
-[0.909904] (-) TimerEvent: {}
-[1.010321] (-) TimerEvent: {}
-[1.110978] (-) TimerEvent: {}
-[1.211530] (-) TimerEvent: {}
-[1.312020] (-) TimerEvent: {}
-[1.412656] (-) TimerEvent: {}
-[1.463225] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/src/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/src/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin/ros2', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'DBUS_STARTER_BUS_TYPE': 'session', 'SYSTEMD_EXEC_PID': '1590', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus,guid=8a156d7e5676347bfc3ac19e67602fa1', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/src/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/app.slice/app-gnome\\x2dsession\\x2dmanager.slice/gnome-session-manager@ubuntu.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1590,unix/robobin-desktop:/tmp/.ICE-unix/1590', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/a852a9e4_da64_4834_8ab2_d5be4b533e22', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.W9TAZ2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.104', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/src/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/src/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'DBUS_STARTER_ADDRESS': 'unix:path=/run/user/1002/bus,guid=8a156d7e5676347bfc3ac19e67602fa1', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.512733] (-) TimerEvent: {}
-[1.613257] (-) TimerEvent: {}
-[1.714188] (-) TimerEvent: {}
-[1.814507] (-) TimerEvent: {}
-[1.913428] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.913948] (robobin) StdoutLine: {'line': b'creating ../build/robobin/robobin.egg-info\n'}
-[1.914560] (-) TimerEvent: {}
-[1.945178] (robobin) StdoutLine: {'line': b'writing ../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.945549] (robobin) StdoutLine: {'line': b'writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.945781] (robobin) StdoutLine: {'line': b'writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.945939] (robobin) StdoutLine: {'line': b'writing requirements to ../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.946083] (robobin) StdoutLine: {'line': b'writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt\n'}
-[1.946205] (robobin) StdoutLine: {'line': b"writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.005274] (robobin) StdoutLine: {'line': b"reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.006532] (robobin) StdoutLine: {'line': b"writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.006815] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.007073] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.007511] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/src/build/robobin/build\n'}
-[2.008808] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/src/build/robobin/build/lib\n'}
-[2.009631] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[2.010022] (robobin) StdoutLine: {'line': b'copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[2.010385] (robobin) StdoutLine: {'line': b'copying robobin/__init__.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[2.010643] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[2.010965] (robobin) StdoutLine: {'line': b'copying robobin/api_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[2.011473] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers\n'}
-[2.011707] (robobin) StdoutLine: {'line': b'copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers\n'}
-[2.012000] (robobin) StdoutLine: {'line': b'copying robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers\n'}
-[2.012233] (robobin) StdoutLine: {'line': b'copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers\n'}
-[2.012905] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.014633] (-) TimerEvent: {}
-[2.022608] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.054680] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.054961] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.055086] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/__init__.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.055204] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.055352] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[2.055468] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[2.055638] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[2.055768] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[2.055924] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.056821] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc\n'}
-[2.058060] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__init__.py to __init__.cpython-312.pyc\n'}
-[2.058308] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.062392] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc\n'}
-[2.065025] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py to __init__.cpython-312.pyc\n'}
-[2.065313] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc\n'}
-[2.066587] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc\n'}
-[2.067920] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.068062] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/src/install/robobin/share/ament_index\n'}
-[2.068169] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index\n'}
-[2.068277] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index/packages\n'}
-[2.068381] (robobin) StdoutLine: {'line': b'copying resource/robobin -> /home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index/packages\n'}
-[2.068513] (robobin) StdoutLine: {'line': b'copying package.xml -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin\n'}
-[2.068663] (robobin) StdoutLine: {'line': b'creating /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch\n'}
-[2.068762] (robobin) StdoutLine: {'line': b'copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch\n'}
-[2.068898] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.098000] (robobin) StdoutLine: {'line': b'Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.099895] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.114762] (-) TimerEvent: {}
-[2.215095] (-) TimerEvent: {}
-[2.315420] (-) TimerEvent: {}
-[2.320811] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.321101] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.321241] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.321759] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'\n"}
-[2.415589] (-) TimerEvent: {}
-[2.425213] (robobin) CommandEnded: {'returncode': 0}
-[2.446822] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.447666] (-) EventReactorShutdown: {}
diff --git a/ros2/src/log/build_2024-12-16_14-16-57/logger_all.log b/ros2/src/log/build_2024-12-16_14-16-57/logger_all.log
deleted file mode 100644
index 962c303d76d8bf8b3108b7ff942ee89f57ccda2a..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_14-16-57/logger_all.log
+++ /dev/null
@@ -1,115 +0,0 @@
-[0.174s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.174s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff847e5430>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff847e5130>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff847e5130>>, mixin_verb=('build',))
-[0.237s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.237s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.238s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.238s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.238s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.238s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.238s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2/src'
-[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.278s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore'
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore_ament_install'
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_pkg']
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_pkg'
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_meta']
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_meta'
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ros']
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ros'
-[0.282s] DEBUG:colcon.colcon_core.package_identification:Package 'robobin' with type 'ros.ament_python' and name 'robobin'
-[0.283s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.283s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.283s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.283s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.283s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.316s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.316s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.318s] WARNING:colcon.colcon_ros.prefix_path.ament:The path '/home/robobin/robobin/ros2/src/install/robobin' in the environment variable AMENT_PREFIX_PATH doesn't exist
-[0.319s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 0 installed packages in /home/robobin/robobin/ros2/src/install
-[0.319s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.322s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.324s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.400s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.401s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/src/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/src/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.401s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.402s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.403s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.403s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.405s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.406s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.410s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.412s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.413s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.414s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.796s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.797s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.797s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.869s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[2.828s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[2.830s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake module files
-[2.831s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake config files
-[2.832s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib'
-[2.832s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[2.832s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/pkgconfig/robobin.pc'
-[2.832s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages'
-[2.833s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.833s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.833s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.834s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.837s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[2.837s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.839s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.ps1'
-[2.841s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.dsv'
-[2.844s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.sh'
-[2.846s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.bash'
-[2.848s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.zsh'
-[2.848s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/src/install/robobin/share/colcon-core/packages/robobin)
-[2.849s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.849s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.849s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.849s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.857s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.857s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.857s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.886s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.887s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.ps1'
-[2.891s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_ps1.py'
-[2.893s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.ps1'
-[2.894s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.sh'
-[2.895s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_sh.py'
-[2.896s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.sh'
-[2.898s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.bash'
-[2.899s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.bash'
-[2.901s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.zsh'
-[2.902s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.zsh'
diff --git a/ros2/src/log/build_2024-12-16_14-16-57/robobin/command.log b/ros2/src/log/build_2024-12-16_14-16-57/robobin/command.log
deleted file mode 100644
index f3802c6a7d0396462088b5e246ef91cbbe9f914c..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_14-16-57/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-16_14-16-57/robobin/stderr.log b/ros2/src/log/build_2024-12-16_14-16-57/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/log/build_2024-12-16_14-16-57/robobin/stdout.log b/ros2/src/log/build_2024-12-16_14-16-57/robobin/stdout.log
deleted file mode 100644
index ccff0cb3df54abc40bdc0c4d320586cd75ccd65a..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_14-16-57/robobin/stdout.log
+++ /dev/null
@@ -1,56 +0,0 @@
-running egg_info
-creating ../build/robobin/robobin.egg-info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-creating /home/robobin/robobin/ros2/src/build/robobin/build
-creating /home/robobin/robobin/ros2/src/build/robobin/build/lib
-creating /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/__init__.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/api_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-creating /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-running install
-running install_lib
-creating /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/__init__.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-creating /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__init__.py to __init__.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py to __init__.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc
-running install_data
-creating /home/robobin/robobin/ros2/src/install/robobin/share/ament_index
-creating /home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index
-creating /home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index/packages
-copying resource/robobin -> /home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index/packages
-copying package.xml -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin
-creating /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-running install_egg_info
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-16_14-16-57/robobin/stdout_stderr.log b/ros2/src/log/build_2024-12-16_14-16-57/robobin/stdout_stderr.log
deleted file mode 100644
index ccff0cb3df54abc40bdc0c4d320586cd75ccd65a..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_14-16-57/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,56 +0,0 @@
-running egg_info
-creating ../build/robobin/robobin.egg-info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-creating /home/robobin/robobin/ros2/src/build/robobin/build
-creating /home/robobin/robobin/ros2/src/build/robobin/build/lib
-creating /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/__init__.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/api_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-creating /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-running install
-running install_lib
-creating /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/__init__.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-creating /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__init__.py to __init__.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py to __init__.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc
-running install_data
-creating /home/robobin/robobin/ros2/src/install/robobin/share/ament_index
-creating /home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index
-creating /home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index/packages
-copying resource/robobin -> /home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index/packages
-copying package.xml -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin
-creating /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-running install_egg_info
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-16_14-16-57/robobin/streams.log b/ros2/src/log/build_2024-12-16_14-16-57/robobin/streams.log
deleted file mode 100644
index 354043defa0f8afd3e2b1e7e22e6249da3847006..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_14-16-57/robobin/streams.log
+++ /dev/null
@@ -1,58 +0,0 @@
-[1.466s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[1.913s] running egg_info
-[1.913s] creating ../build/robobin/robobin.egg-info
-[1.945s] writing ../build/robobin/robobin.egg-info/PKG-INFO
-[1.945s] writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-[1.945s] writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-[1.945s] writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-[1.945s] writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-[1.946s] writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.005s] reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.006s] writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.006s] running build
-[2.007s] running build_py
-[2.007s] creating /home/robobin/robobin/ros2/src/build/robobin/build
-[2.009s] creating /home/robobin/robobin/ros2/src/build/robobin/build/lib
-[2.009s] creating /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[2.009s] copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[2.010s] copying robobin/__init__.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[2.010s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[2.010s] copying robobin/api_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[2.011s] creating /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-[2.011s] copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-[2.011s] copying robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-[2.012s] copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-[2.012s] running install
-[2.022s] running install_lib
-[2.054s] creating /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[2.054s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[2.054s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/__init__.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[2.055s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[2.055s] creating /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[2.055s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[2.055s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/__init__.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[2.055s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[2.055s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[2.056s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc
-[2.057s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/__init__.py to __init__.cpython-312.pyc
-[2.058s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.062s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc
-[2.065s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/__init__.py to __init__.cpython-312.pyc
-[2.065s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc
-[2.066s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc
-[2.067s] running install_data
-[2.067s] creating /home/robobin/robobin/ros2/src/install/robobin/share/ament_index
-[2.068s] creating /home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index
-[2.068s] creating /home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index/packages
-[2.068s] copying resource/robobin -> /home/robobin/robobin/ros2/src/install/robobin/share/ament_index/resource_index/packages
-[2.068s] copying package.xml -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin
-[2.068s] creating /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-[2.068s] copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-[2.068s] running install_egg_info
-[2.098s] Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.100s] running install_scripts
-[2.320s] Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.320s] Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.321s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.321s] writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
-[2.425s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-16_16-11-35/events.log b/ros2/src/log/build_2024-12-16_16-11-35/events.log
deleted file mode 100644
index f2ddf12216069e827cbc532d60c3426f17fa04e1..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-11-35/events.log
+++ /dev/null
@@ -1,63 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000614] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.001050] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099553] (-) TimerEvent: {}
-[0.200121] (-) TimerEvent: {}
-[0.300746] (-) TimerEvent: {}
-[0.401420] (-) TimerEvent: {}
-[0.502878] (-) TimerEvent: {}
-[0.603595] (-) TimerEvent: {}
-[0.704268] (-) TimerEvent: {}
-[0.804903] (-) TimerEvent: {}
-[0.906027] (-) TimerEvent: {}
-[1.006628] (-) TimerEvent: {}
-[1.107131] (-) TimerEvent: {}
-[1.207751] (-) TimerEvent: {}
-[1.310236] (-) TimerEvent: {}
-[1.410775] (-) TimerEvent: {}
-[1.511228] (-) TimerEvent: {}
-[1.611658] (-) TimerEvent: {}
-[1.712170] (-) TimerEvent: {}
-[1.812605] (-) TimerEvent: {}
-[1.913279] (-) TimerEvent: {}
-[2.013904] (-) TimerEvent: {}
-[2.021569] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/src/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/src/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin/ros2', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'DBUS_STARTER_BUS_TYPE': 'session', 'SYSTEMD_EXEC_PID': '1594', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/app.slice/app-gnome\\x2dsession\\x2dmanager.slice/gnome-session-manager@ubuntu.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1594,unix/robobin-desktop:/tmp/.ICE-unix/1594', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/92f2849b_1746_4562_850c_1b14829cbe47', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.XGQ7Y2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.102', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/src/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'DBUS_STARTER_ADDRESS': 'unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[2.114101] (-) TimerEvent: {}
-[2.214691] (-) TimerEvent: {}
-[2.315084] (-) TimerEvent: {}
-[2.415604] (-) TimerEvent: {}
-[2.515998] (-) TimerEvent: {}
-[2.573610] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[2.616147] (-) TimerEvent: {}
-[2.616916] (robobin) StdoutLine: {'line': b'writing ../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[2.617539] (robobin) StdoutLine: {'line': b'writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[2.618916] (robobin) StdoutLine: {'line': b'writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[2.619645] (robobin) StdoutLine: {'line': b'writing requirements to ../build/robobin/robobin.egg-info/requires.txt\n'}
-[2.619911] (robobin) StdoutLine: {'line': b'writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.687696] (robobin) StdoutLine: {'line': b"reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.689598] (robobin) StdoutLine: {'line': b"writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.689914] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.690128] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.690588] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[2.691270] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.705661] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.716234] (-) TimerEvent: {}
-[2.748412] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.750739] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.757831] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.758175] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.795601] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.799156] (robobin) StdoutLine: {'line': b'Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.800208] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.816404] (-) TimerEvent: {}
-[2.916820] (-) TimerEvent: {}
-[3.021162] (-) TimerEvent: {}
-[3.085333] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[3.085667] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[3.087660] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[3.091563] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'\n"}
-[3.121720] (-) TimerEvent: {}
-[3.218013] (robobin) CommandEnded: {'returncode': 0}
-[3.221743] (-) TimerEvent: {}
-[3.248648] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[3.251739] (-) EventReactorShutdown: {}
diff --git a/ros2/src/log/build_2024-12-16_16-11-35/logger_all.log b/ros2/src/log/build_2024-12-16_16-11-35/logger_all.log
deleted file mode 100644
index 22e4eecfd4e33fe8ba735fb46fdcbb79504f0db4..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-11-35/logger_all.log
+++ /dev/null
@@ -1,113 +0,0 @@
-[0.186s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.187s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff9ae114c0>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff9ae111f0>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff9ae111f0>>, mixin_verb=('build',))
-[0.262s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.262s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.262s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.263s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.263s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.263s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.263s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2/src'
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.263s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.264s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.338s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.339s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.339s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.339s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.339s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.339s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.339s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.339s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.339s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.339s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore'
-[0.339s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore_ament_install'
-[0.340s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_pkg']
-[0.340s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_pkg'
-[0.340s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_meta']
-[0.340s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_meta'
-[0.340s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ros']
-[0.340s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ros'
-[0.343s] DEBUG:colcon.colcon_core.package_identification:Package 'robobin' with type 'ros.ament_python' and name 'robobin'
-[0.343s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.343s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.343s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.343s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.343s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.372s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.372s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.376s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.379s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.384s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.468s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.468s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.468s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.469s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.469s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.470s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.470s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.470s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.470s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.471s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/src/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/src/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.471s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.473s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.473s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.474s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.477s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.478s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.481s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.484s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.487s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.487s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.039s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[1.040s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[1.040s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[2.499s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[3.691s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[3.697s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake module files
-[3.698s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake config files
-[3.702s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib'
-[3.703s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[3.704s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/pkgconfig/robobin.pc'
-[3.705s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages'
-[3.706s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[3.707s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.ps1'
-[3.708s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.dsv'
-[3.713s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.sh'
-[3.714s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[3.714s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[3.715s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.ps1'
-[3.716s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.dsv'
-[3.717s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.sh'
-[3.718s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.bash'
-[3.720s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.zsh'
-[3.720s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/src/install/robobin/share/colcon-core/packages/robobin)
-[3.721s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[3.723s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[3.723s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[3.723s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[3.738s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[3.738s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[3.738s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[3.765s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[3.767s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.ps1'
-[3.770s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_ps1.py'
-[3.772s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.ps1'
-[3.774s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.sh'
-[3.777s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_sh.py'
-[3.778s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.sh'
-[3.781s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.bash'
-[3.783s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.bash'
-[3.786s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.zsh'
-[3.788s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.zsh'
diff --git a/ros2/src/log/build_2024-12-16_16-11-35/robobin/command.log b/ros2/src/log/build_2024-12-16_16-11-35/robobin/command.log
deleted file mode 100644
index f3802c6a7d0396462088b5e246ef91cbbe9f914c..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-11-35/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-16_16-11-35/robobin/stderr.log b/ros2/src/log/build_2024-12-16_16-11-35/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/log/build_2024-12-16_16-11-35/robobin/stdout.log b/ros2/src/log/build_2024-12-16_16-11-35/robobin/stdout.log
deleted file mode 100644
index 43010dadd2f8465b171023262815770b2fc5fc48..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-11-35/robobin/stdout.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-16_16-11-35/robobin/stdout_stderr.log b/ros2/src/log/build_2024-12-16_16-11-35/robobin/stdout_stderr.log
deleted file mode 100644
index 43010dadd2f8465b171023262815770b2fc5fc48..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-11-35/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-16_16-11-35/robobin/streams.log b/ros2/src/log/build_2024-12-16_16-11-35/robobin/streams.log
deleted file mode 100644
index f7e6dd974fe9ac62a673b71b002eb444a14d8f79..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-11-35/robobin/streams.log
+++ /dev/null
@@ -1,26 +0,0 @@
-[2.024s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[2.573s] running egg_info
-[2.616s] writing ../build/robobin/robobin.egg-info/PKG-INFO
-[2.617s] writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-[2.618s] writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-[2.619s] writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-[2.619s] writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-[2.687s] reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.689s] writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.689s] running build
-[2.689s] running build_py
-[2.690s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[2.690s] running install
-[2.705s] running install_lib
-[2.748s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[2.750s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.757s] running install_data
-[2.757s] running install_egg_info
-[2.795s] removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.798s] Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.799s] running install_scripts
-[3.085s] Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[3.085s] Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[3.087s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[3.091s] writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
-[3.217s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-16_16-14-21/events.log b/ros2/src/log/build_2024-12-16_16-14-21/events.log
deleted file mode 100644
index 40249220b8aac28a11db50f3e87be1fb6db1862b..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-14-21/events.log
+++ /dev/null
@@ -1,75 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.001475] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.001867] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099671] (-) TimerEvent: {}
-[0.204752] (-) TimerEvent: {}
-[0.306567] (-) TimerEvent: {}
-[0.410978] (-) TimerEvent: {}
-[0.514672] (-) TimerEvent: {}
-[0.615652] (-) TimerEvent: {}
-[0.718401] (-) TimerEvent: {}
-[0.819823] (-) TimerEvent: {}
-[0.923491] (-) TimerEvent: {}
-[1.024299] (-) TimerEvent: {}
-[1.125221] (-) TimerEvent: {}
-[1.229223] (-) TimerEvent: {}
-[1.330711] (-) TimerEvent: {}
-[1.431555] (-) TimerEvent: {}
-[1.537216] (-) TimerEvent: {}
-[1.638084] (-) TimerEvent: {}
-[1.740503] (-) TimerEvent: {}
-[1.840915] (-) TimerEvent: {}
-[1.945168] (-) TimerEvent: {}
-[2.045730] (-) TimerEvent: {}
-[2.146212] (-) TimerEvent: {}
-[2.248404] (-) TimerEvent: {}
-[2.348783] (-) TimerEvent: {}
-[2.451538] (-) TimerEvent: {}
-[2.553321] (-) TimerEvent: {}
-[2.654055] (-) TimerEvent: {}
-[2.760586] (-) TimerEvent: {}
-[2.861795] (-) TimerEvent: {}
-[2.962844] (-) TimerEvent: {}
-[3.006999] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/src/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/src/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin/ros2', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'DBUS_STARTER_BUS_TYPE': 'session', 'SYSTEMD_EXEC_PID': '1594', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/src/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/app.slice/app-gnome\\x2dsession\\x2dmanager.slice/gnome-session-manager@ubuntu.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1594,unix/robobin-desktop:/tmp/.ICE-unix/1594', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/92f2849b_1746_4562_850c_1b14829cbe47', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.XGQ7Y2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.102', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/src/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/src/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'DBUS_STARTER_ADDRESS': 'unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[3.062953] (-) TimerEvent: {}
-[3.164014] (-) TimerEvent: {}
-[3.264832] (-) TimerEvent: {}
-[3.365680] (-) TimerEvent: {}
-[3.466696] (-) TimerEvent: {}
-[3.567365] (-) TimerEvent: {}
-[3.667818] (-) TimerEvent: {}
-[3.737782] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[3.767998] (-) TimerEvent: {}
-[3.788708] (robobin) StdoutLine: {'line': b'writing ../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[3.789913] (robobin) StdoutLine: {'line': b'writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[3.791263] (robobin) StdoutLine: {'line': b'writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[3.792437] (robobin) StdoutLine: {'line': b'writing requirements to ../build/robobin/robobin.egg-info/requires.txt\n'}
-[3.793120] (robobin) StdoutLine: {'line': b'writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt\n'}
-[3.868110] (-) TimerEvent: {}
-[3.904763] (robobin) StdoutLine: {'line': b"reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[3.910456] (robobin) StdoutLine: {'line': b"writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[3.911817] (robobin) StdoutLine: {'line': b'running build\n'}
-[3.912422] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[3.912908] (robobin) StdoutLine: {'line': b'running install\n'}
-[3.930443] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[3.968318] (-) TimerEvent: {}
-[3.992603] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[3.994353] (robobin) StdoutLine: {'line': b'copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch\n'}
-[3.995889] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[4.067594] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[4.069521] (robobin) StdoutLine: {'line': b'Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[4.069838] (-) TimerEvent: {}
-[4.071312] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[4.170054] (-) TimerEvent: {}
-[4.271077] (-) TimerEvent: {}
-[4.372030] (-) TimerEvent: {}
-[4.436545] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[4.437290] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[4.437944] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[4.439216] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'\n"}
-[4.472221] (-) TimerEvent: {}
-[4.573017] (-) TimerEvent: {}
-[4.653904] (robobin) CommandEnded: {'returncode': 0}
-[4.673997] (-) TimerEvent: {}
-[4.714561] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[4.722859] (-) EventReactorShutdown: {}
diff --git a/ros2/src/log/build_2024-12-16_16-14-21/logger_all.log b/ros2/src/log/build_2024-12-16_16-14-21/logger_all.log
deleted file mode 100644
index 41d09a7be99ba710430215f7742c37787ef8ee77..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-14-21/logger_all.log
+++ /dev/null
@@ -1,114 +0,0 @@
-[0.361s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.361s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffffbab15850>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffffbab15520>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffffbab15520>>, mixin_verb=('build',))
-[0.481s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.483s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.483s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.483s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.483s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.484s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.484s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2/src'
-[0.485s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.486s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.487s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.488s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.489s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.489s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.489s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.489s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.489s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.571s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.572s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.572s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.572s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.572s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.573s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.573s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.573s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.574s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.575s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.575s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.575s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.575s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.576s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.576s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.576s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore'
-[0.576s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore_ament_install'
-[0.576s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_pkg']
-[0.576s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_pkg'
-[0.577s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_meta']
-[0.577s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_meta'
-[0.577s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ros']
-[0.577s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ros'
-[0.585s] DEBUG:colcon.colcon_core.package_identification:Package 'robobin' with type 'ros.ament_python' and name 'robobin'
-[0.586s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.586s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.586s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.586s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.586s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.635s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.635s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.639s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/src/install
-[0.640s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.643s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.647s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.761s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.761s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.761s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.761s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.761s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.761s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.762s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.762s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.762s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.762s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/src/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/src/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.762s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.764s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.764s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.764s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.771s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.771s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.773s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.774s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.776s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.776s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.811s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[1.812s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[1.812s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[3.783s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[5.418s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[5.430s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake module files
-[5.430s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake config files
-[5.432s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib'
-[5.432s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[5.432s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/pkgconfig/robobin.pc'
-[5.433s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages'
-[5.433s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[5.433s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.ps1'
-[5.434s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.dsv'
-[5.435s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.sh'
-[5.436s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[5.437s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[5.437s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.ps1'
-[5.451s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.dsv'
-[5.457s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.sh'
-[5.464s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.bash'
-[5.468s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.zsh'
-[5.474s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/src/install/robobin/share/colcon-core/packages/robobin)
-[5.476s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[5.477s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[5.477s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[5.477s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[5.525s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[5.527s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[5.528s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[5.586s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[5.589s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.ps1'
-[5.592s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_ps1.py'
-[5.595s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.ps1'
-[5.598s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.sh'
-[5.599s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_sh.py'
-[5.601s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.sh'
-[5.604s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.bash'
-[5.606s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.bash'
-[5.608s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.zsh'
-[5.611s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.zsh'
diff --git a/ros2/src/log/build_2024-12-16_16-14-21/robobin/command.log b/ros2/src/log/build_2024-12-16_16-14-21/robobin/command.log
deleted file mode 100644
index f3802c6a7d0396462088b5e246ef91cbbe9f914c..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-14-21/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-16_16-14-21/robobin/stderr.log b/ros2/src/log/build_2024-12-16_16-14-21/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/log/build_2024-12-16_16-14-21/robobin/stdout.log b/ros2/src/log/build_2024-12-16_16-14-21/robobin/stdout.log
deleted file mode 100644
index 366e1c6e7be6d7bc4a850d1392c4f3ae3d8721bb..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-14-21/robobin/stdout.log
+++ /dev/null
@@ -1,22 +0,0 @@
-running egg_info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-running install
-running install_lib
-running install_data
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-running install_egg_info
-removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-16_16-14-21/robobin/stdout_stderr.log b/ros2/src/log/build_2024-12-16_16-14-21/robobin/stdout_stderr.log
deleted file mode 100644
index 366e1c6e7be6d7bc4a850d1392c4f3ae3d8721bb..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-14-21/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,22 +0,0 @@
-running egg_info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-running install
-running install_lib
-running install_data
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-running install_egg_info
-removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-16_16-14-21/robobin/streams.log b/ros2/src/log/build_2024-12-16_16-14-21/robobin/streams.log
deleted file mode 100644
index 9dd959b47df7adc08311972c583b95e999ffc17f..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-14-21/robobin/streams.log
+++ /dev/null
@@ -1,24 +0,0 @@
-[3.017s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[3.736s] running egg_info
-[3.787s] writing ../build/robobin/robobin.egg-info/PKG-INFO
-[3.788s] writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-[3.789s] writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-[3.790s] writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-[3.791s] writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-[3.903s] reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[3.909s] writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[3.910s] running build
-[3.911s] running build_py
-[3.911s] running install
-[3.929s] running install_lib
-[3.991s] running install_data
-[3.993s] copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-[3.994s] running install_egg_info
-[4.066s] removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[4.068s] Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[4.070s] running install_scripts
-[4.435s] Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[4.435s] Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[4.436s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[4.437s] writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
-[4.652s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-16_16-15-31/events.log b/ros2/src/log/build_2024-12-16_16-15-31/events.log
deleted file mode 100644
index bb34dc18f5b159aa85c38bac88050ed4fcb321e1..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-15-31/events.log
+++ /dev/null
@@ -1,61 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000410] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000792] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099670] (-) TimerEvent: {}
-[0.200041] (-) TimerEvent: {}
-[0.300399] (-) TimerEvent: {}
-[0.400747] (-) TimerEvent: {}
-[0.501233] (-) TimerEvent: {}
-[0.603378] (-) TimerEvent: {}
-[0.704599] (-) TimerEvent: {}
-[0.805136] (-) TimerEvent: {}
-[0.905698] (-) TimerEvent: {}
-[1.006021] (-) TimerEvent: {}
-[1.108739] (-) TimerEvent: {}
-[1.209072] (-) TimerEvent: {}
-[1.311764] (-) TimerEvent: {}
-[1.412105] (-) TimerEvent: {}
-[1.512473] (-) TimerEvent: {}
-[1.612878] (-) TimerEvent: {}
-[1.713590] (-) TimerEvent: {}
-[1.814055] (-) TimerEvent: {}
-[1.860085] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/src/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/src/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin/ros2', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'DBUS_STARTER_BUS_TYPE': 'session', 'SYSTEMD_EXEC_PID': '1594', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/src/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/app.slice/app-gnome\\x2dsession\\x2dmanager.slice/gnome-session-manager@ubuntu.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1594,unix/robobin-desktop:/tmp/.ICE-unix/1594', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/92f2849b_1746_4562_850c_1b14829cbe47', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.XGQ7Y2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.102', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/src/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/src/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'DBUS_STARTER_ADDRESS': 'unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.914169] (-) TimerEvent: {}
-[2.014544] (-) TimerEvent: {}
-[2.114866] (-) TimerEvent: {}
-[2.215188] (-) TimerEvent: {}
-[2.315520] (-) TimerEvent: {}
-[2.375167] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[2.404525] (robobin) StdoutLine: {'line': b'writing ../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[2.404966] (robobin) StdoutLine: {'line': b'writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[2.407004] (robobin) StdoutLine: {'line': b'writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[2.407537] (robobin) StdoutLine: {'line': b'writing requirements to ../build/robobin/robobin.egg-info/requires.txt\n'}
-[2.408281] (robobin) StdoutLine: {'line': b'writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.415574] (-) TimerEvent: {}
-[2.489260] (robobin) StdoutLine: {'line': b"reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.490424] (robobin) StdoutLine: {'line': b"writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.490701] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.490876] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.491090] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[2.491888] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.501293] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.515665] (-) TimerEvent: {}
-[2.540452] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.542406] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.549922] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.550417] (robobin) StdoutLine: {'line': b'copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch\n'}
-[2.550647] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.586418] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.587127] (robobin) StdoutLine: {'line': b'Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.588313] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.615770] (-) TimerEvent: {}
-[2.716084] (-) TimerEvent: {}
-[2.816403] (-) TimerEvent: {}
-[2.842281] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.842989] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.845018] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.846859] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'\n"}
-[2.916575] (-) TimerEvent: {}
-[2.982520] (robobin) CommandEnded: {'returncode': 0}
-[3.002063] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[3.003758] (-) EventReactorShutdown: {}
diff --git a/ros2/src/log/build_2024-12-16_16-15-31/logger_all.log b/ros2/src/log/build_2024-12-16_16-15-31/logger_all.log
deleted file mode 100644
index b2164934ea9070fd9795b8d26cc5829f660dd3e1..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-15-31/logger_all.log
+++ /dev/null
@@ -1,114 +0,0 @@
-[0.187s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.187s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff8a16d3d0>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff8a16d100>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff8a16d100>>, mixin_verb=('build',))
-[0.247s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.248s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.248s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.248s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.248s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.248s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.248s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2/src'
-[0.248s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.249s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.305s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.305s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.305s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.305s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.305s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.306s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.306s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.306s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.306s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.306s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.306s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.306s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.306s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.306s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.306s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.306s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore'
-[0.307s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore_ament_install'
-[0.307s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_pkg']
-[0.307s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_pkg'
-[0.307s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_meta']
-[0.307s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_meta'
-[0.307s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ros']
-[0.307s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ros'
-[0.310s] DEBUG:colcon.colcon_core.package_identification:Package 'robobin' with type 'ros.ament_python' and name 'robobin'
-[0.310s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.310s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.310s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.310s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.310s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.335s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.335s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.337s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/src/install
-[0.338s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.340s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.343s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.424s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.425s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.425s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.425s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.425s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.425s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.425s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.425s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.425s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.425s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/src/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/src/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.425s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.427s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.427s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.427s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.433s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.434s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.435s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.438s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.441s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.441s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.029s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[1.030s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[1.030s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[2.292s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[3.409s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[3.413s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake module files
-[3.414s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake config files
-[3.415s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib'
-[3.415s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[3.416s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/pkgconfig/robobin.pc'
-[3.416s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages'
-[3.416s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[3.416s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.ps1'
-[3.417s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.dsv'
-[3.418s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.sh'
-[3.420s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[3.420s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[3.420s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.ps1'
-[3.421s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.dsv'
-[3.423s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.sh'
-[3.424s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.bash'
-[3.425s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.zsh'
-[3.427s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/src/install/robobin/share/colcon-core/packages/robobin)
-[3.428s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[3.429s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[3.429s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[3.429s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[3.451s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[3.452s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[3.452s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[3.487s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[3.487s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.ps1'
-[3.489s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_ps1.py'
-[3.490s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.ps1'
-[3.492s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.sh'
-[3.494s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_sh.py'
-[3.497s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.sh'
-[3.500s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.bash'
-[3.501s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.bash'
-[3.502s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.zsh'
-[3.505s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.zsh'
diff --git a/ros2/src/log/build_2024-12-16_16-15-31/robobin/command.log b/ros2/src/log/build_2024-12-16_16-15-31/robobin/command.log
deleted file mode 100644
index f3802c6a7d0396462088b5e246ef91cbbe9f914c..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-15-31/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-16_16-15-31/robobin/stderr.log b/ros2/src/log/build_2024-12-16_16-15-31/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/log/build_2024-12-16_16-15-31/robobin/stdout.log b/ros2/src/log/build_2024-12-16_16-15-31/robobin/stdout.log
deleted file mode 100644
index dd2a82542020da944d8da8f514d0cfa938c8c6f6..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-15-31/robobin/stdout.log
+++ /dev/null
@@ -1,25 +0,0 @@
-running egg_info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-running install_egg_info
-removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-16_16-15-31/robobin/stdout_stderr.log b/ros2/src/log/build_2024-12-16_16-15-31/robobin/stdout_stderr.log
deleted file mode 100644
index dd2a82542020da944d8da8f514d0cfa938c8c6f6..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-15-31/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,25 +0,0 @@
-running egg_info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-running install_egg_info
-removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-16_16-15-31/robobin/streams.log b/ros2/src/log/build_2024-12-16_16-15-31/robobin/streams.log
deleted file mode 100644
index 6ff9e31da92cf86bcb2884c7a357694c04820876..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-15-31/robobin/streams.log
+++ /dev/null
@@ -1,27 +0,0 @@
-[1.864s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[2.375s] running egg_info
-[2.403s] writing ../build/robobin/robobin.egg-info/PKG-INFO
-[2.404s] writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-[2.406s] writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-[2.406s] writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-[2.407s] writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-[2.488s] reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.489s] writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.490s] running build
-[2.490s] running build_py
-[2.490s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[2.491s] running install
-[2.500s] running install_lib
-[2.540s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[2.541s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.549s] running install_data
-[2.549s] copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-[2.549s] running install_egg_info
-[2.586s] removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.586s] Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.587s] running install_scripts
-[2.841s] Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.842s] Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.844s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.846s] writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
-[2.982s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-16_16-24-23/events.log b/ros2/src/log/build_2024-12-16_16-24-23/events.log
deleted file mode 100644
index e2b4d9e9617253c79a299d6411fee1979991f738..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-24-23/events.log
+++ /dev/null
@@ -1,60 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000510] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.002282] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.100162] (-) TimerEvent: {}
-[0.202134] (-) TimerEvent: {}
-[0.302862] (-) TimerEvent: {}
-[0.403624] (-) TimerEvent: {}
-[0.504692] (-) TimerEvent: {}
-[0.605564] (-) TimerEvent: {}
-[0.706058] (-) TimerEvent: {}
-[0.806504] (-) TimerEvent: {}
-[0.906917] (-) TimerEvent: {}
-[1.007371] (-) TimerEvent: {}
-[1.107756] (-) TimerEvent: {}
-[1.208157] (-) TimerEvent: {}
-[1.308538] (-) TimerEvent: {}
-[1.408884] (-) TimerEvent: {}
-[1.509232] (-) TimerEvent: {}
-[1.609551] (-) TimerEvent: {}
-[1.709872] (-) TimerEvent: {}
-[1.810240] (-) TimerEvent: {}
-[1.906370] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/src/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/src/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin/ros2', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'DBUS_STARTER_BUS_TYPE': 'session', 'SYSTEMD_EXEC_PID': '1594', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/src/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/app.slice/app-gnome\\x2dsession\\x2dmanager.slice/gnome-session-manager@ubuntu.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1594,unix/robobin-desktop:/tmp/.ICE-unix/1594', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/92f2849b_1746_4562_850c_1b14829cbe47', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.XGQ7Y2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.102', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/src/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/src/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'DBUS_STARTER_ADDRESS': 'unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.910322] (-) TimerEvent: {}
-[2.014187] (-) TimerEvent: {}
-[2.114588] (-) TimerEvent: {}
-[2.214916] (-) TimerEvent: {}
-[2.315344] (-) TimerEvent: {}
-[2.394494] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[2.415396] (-) TimerEvent: {}
-[2.430683] (robobin) StdoutLine: {'line': b'writing ../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[2.431726] (robobin) StdoutLine: {'line': b'writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[2.432877] (robobin) StdoutLine: {'line': b'writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[2.434292] (robobin) StdoutLine: {'line': b'writing requirements to ../build/robobin/robobin.egg-info/requires.txt\n'}
-[2.435608] (robobin) StdoutLine: {'line': b'writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.498723] (robobin) StdoutLine: {'line': b"reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.499895] (robobin) StdoutLine: {'line': b"writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.500190] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.500342] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.500570] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[2.501363] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.510950] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.515468] (-) TimerEvent: {}
-[2.553141] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[2.554067] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[2.559555] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.559793] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.591178] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.591669] (robobin) StdoutLine: {'line': b'Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.592916] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.615538] (-) TimerEvent: {}
-[2.715883] (-) TimerEvent: {}
-[2.816515] (-) TimerEvent: {}
-[2.827731] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.829341] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.831564] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.833375] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'\n"}
-[2.916599] (-) TimerEvent: {}
-[2.958339] (robobin) CommandEnded: {'returncode': 0}
-[2.974722] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.976214] (-) EventReactorShutdown: {}
diff --git a/ros2/src/log/build_2024-12-16_16-24-23/logger_all.log b/ros2/src/log/build_2024-12-16_16-24-23/logger_all.log
deleted file mode 100644
index d05791d88d1498d9f1a6ae0f1fcb7aeeaad91f4c..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-24-23/logger_all.log
+++ /dev/null
@@ -1,114 +0,0 @@
-[0.452s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.452s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffff8646d400>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffff8646d190>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffff8646d190>>, mixin_verb=('build',))
-[0.639s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.640s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.640s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.640s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.640s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.640s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.640s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2/src'
-[0.641s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.641s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.641s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.642s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.642s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.642s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.642s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.642s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.642s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.749s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.750s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.750s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.750s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.750s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.751s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.752s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.752s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.753s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.753s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.753s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.754s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.755s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.756s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.756s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.757s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore'
-[0.758s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore_ament_install'
-[0.758s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_pkg']
-[0.758s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_pkg'
-[0.758s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_meta']
-[0.758s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_meta'
-[0.759s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ros']
-[0.759s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ros'
-[0.769s] DEBUG:colcon.colcon_core.package_identification:Package 'robobin' with type 'ros.ament_python' and name 'robobin'
-[0.770s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.771s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.771s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.771s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.771s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.859s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.859s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.869s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/src/install
-[0.872s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.877s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.887s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[1.065s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[1.066s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[1.067s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[1.067s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[1.067s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[1.068s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[1.068s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[1.068s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[1.068s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[1.068s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/src/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/src/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[1.069s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[1.073s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[1.075s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[1.077s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[1.089s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[1.090s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[1.099s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[1.105s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[1.110s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[1.111s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.904s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[1.905s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[1.905s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[2.982s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[4.033s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[4.036s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake module files
-[4.037s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake config files
-[4.038s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib'
-[4.038s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[4.038s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/pkgconfig/robobin.pc'
-[4.039s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages'
-[4.039s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[4.039s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.ps1'
-[4.040s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.dsv'
-[4.041s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.sh'
-[4.042s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[4.042s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[4.042s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.ps1'
-[4.043s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.dsv'
-[4.044s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.sh'
-[4.045s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.bash'
-[4.046s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.zsh'
-[4.047s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/src/install/robobin/share/colcon-core/packages/robobin)
-[4.048s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[4.049s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[4.049s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[4.049s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[4.068s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[4.069s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[4.069s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[4.101s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[4.102s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.ps1'
-[4.104s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_ps1.py'
-[4.106s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.ps1'
-[4.107s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.sh'
-[4.109s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_sh.py'
-[4.110s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.sh'
-[4.113s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.bash'
-[4.118s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.bash'
-[4.120s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.zsh'
-[4.121s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.zsh'
diff --git a/ros2/src/log/build_2024-12-16_16-24-23/robobin/command.log b/ros2/src/log/build_2024-12-16_16-24-23/robobin/command.log
deleted file mode 100644
index f3802c6a7d0396462088b5e246ef91cbbe9f914c..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-24-23/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-16_16-24-23/robobin/stderr.log b/ros2/src/log/build_2024-12-16_16-24-23/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/log/build_2024-12-16_16-24-23/robobin/stdout.log b/ros2/src/log/build_2024-12-16_16-24-23/robobin/stdout.log
deleted file mode 100644
index 43010dadd2f8465b171023262815770b2fc5fc48..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-24-23/robobin/stdout.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-16_16-24-23/robobin/stdout_stderr.log b/ros2/src/log/build_2024-12-16_16-24-23/robobin/stdout_stderr.log
deleted file mode 100644
index 43010dadd2f8465b171023262815770b2fc5fc48..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-24-23/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,24 +0,0 @@
-running egg_info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-16_16-24-23/robobin/streams.log b/ros2/src/log/build_2024-12-16_16-24-23/robobin/streams.log
deleted file mode 100644
index 945b66f7b25477b3a6505ef93dff6977426eceee..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-24-23/robobin/streams.log
+++ /dev/null
@@ -1,26 +0,0 @@
-[1.906s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[2.392s] running egg_info
-[2.429s] writing ../build/robobin/robobin.egg-info/PKG-INFO
-[2.429s] writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-[2.431s] writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-[2.432s] writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-[2.433s] writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-[2.496s] reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.498s] writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.498s] running build
-[2.498s] running build_py
-[2.498s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[2.499s] running install
-[2.509s] running install_lib
-[2.551s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[2.552s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[2.557s] running install_data
-[2.557s] running install_egg_info
-[2.589s] removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.589s] Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.591s] running install_scripts
-[2.826s] Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.828s] Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.830s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.831s] writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
-[2.956s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-16_16-27-14/events.log b/ros2/src/log/build_2024-12-16_16-27-14/events.log
deleted file mode 100644
index 6ce822e09265ee09202b6810fa5a18216c317bc0..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-27-14/events.log
+++ /dev/null
@@ -1,57 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000426] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.001498] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099802] (-) TimerEvent: {}
-[0.200321] (-) TimerEvent: {}
-[0.300682] (-) TimerEvent: {}
-[0.401132] (-) TimerEvent: {}
-[0.505681] (-) TimerEvent: {}
-[0.612977] (-) TimerEvent: {}
-[0.714248] (-) TimerEvent: {}
-[0.816114] (-) TimerEvent: {}
-[0.917107] (-) TimerEvent: {}
-[1.017875] (-) TimerEvent: {}
-[1.119527] (-) TimerEvent: {}
-[1.220191] (-) TimerEvent: {}
-[1.322690] (-) TimerEvent: {}
-[1.423159] (-) TimerEvent: {}
-[1.523675] (-) TimerEvent: {}
-[1.624204] (-) TimerEvent: {}
-[1.724795] (-) TimerEvent: {}
-[1.825425] (-) TimerEvent: {}
-[1.900881] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/src/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/src/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'wayland', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin/ros2', 'DESKTOP_SESSION': 'ubuntu', 'ROS_PYTHON_VERSION': '3', 'GNOME_SHELL_SESSION_MODE': 'ubuntu', 'GTK_MODULES': 'gail:atk-bridge', 'DBUS_STARTER_BUS_TYPE': 'session', 'SYSTEMD_EXEC_PID': '1594', 'GSM_SKIP_SSH_AGENT_WORKAROUND': 'true', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a', 'COLORTERM': 'truecolor', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'IM_CONFIG_PHASE': '1', 'WAYLAND_DISPLAY': 'wayland-0', 'COLCON_PREFIX_PATH': '/home/robobin/robobin/ros2/src/install:/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'MEMORY_PRESSURE_WATCH': '/sys/fs/cgroup/user.slice/user-1002.slice/user@1002.service/app.slice/app-gnome\\x2dsession\\x2dmanager.slice/gnome-session-manager@ubuntu.service/memory.pressure', 'XDG_SESSION_CLASS': 'user', 'USERNAME': 'robobin', 'TERM': 'xterm-256color', 'GNOME_DESKTOP_SESSION_ID': 'this-is-deprecated', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin:/snap/bin', 'SESSION_MANAGER': 'local/robobin-desktop:@/tmp/.ICE-unix/1594,unix/robobin-desktop:/tmp/.ICE-unix/1594', 'XDG_MENU_PREFIX': 'gnome-', 'GNOME_TERMINAL_SCREEN': '/org/gnome/Terminal/screen/92f2849b_1746_4562_850c_1b14829cbe47', 'GNOME_SETUP_DISPLAY': ':1', 'XDG_RUNTIME_DIR': '/run/user/1002', 'DISPLAY': ':0', 'LANG': 'en_US.UTF-8', 'XDG_CURRENT_DESKTOP': 'ubuntu:GNOME', 'XMODIFIERS': '@im=ibus', 'XDG_SESSION_DESKTOP': 'ubuntu', 'XAUTHORITY': '/run/user/1002/.mutter-Xwaylandauth.XGQ7Y2', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'GNOME_TERMINAL_SERVICE': ':1.102', 'SSH_AUTH_SOCK': '/run/user/1002/keyring/ssh', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/robobin/ros2/src/install/robobin:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'QT_ACCESSIBILITY': '1', 'GDMSESSION': 'ubuntu', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'QT_IM_MODULE': 'ibus', 'PWD': '/home/robobin/robobin/ros2/src/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'XDG_CONFIG_DIRS': '/etc/xdg/xdg-ubuntu:/etc/xdg', 'DBUS_STARTER_ADDRESS': 'unix:path=/run/user/1002/bus,guid=4df305406471baf1ac725d2967604c5a', 'XDG_DATA_DIRS': '/usr/share/ubuntu:/usr/share/gnome:/usr/local/share/:/usr/share/:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'MEMORY_PRESSURE_WRITE': 'c29tZSAyMDAwMDAgMjAwMDAwMAA=', 'VTE_VERSION': '7600', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.925579] (-) TimerEvent: {}
-[2.026066] (-) TimerEvent: {}
-[2.126441] (-) TimerEvent: {}
-[2.226992] (-) TimerEvent: {}
-[2.327614] (-) TimerEvent: {}
-[2.391933] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[2.424131] (robobin) StdoutLine: {'line': b'writing ../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[2.427674] (-) TimerEvent: {}
-[2.432860] (robobin) StdoutLine: {'line': b'writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[2.433769] (robobin) StdoutLine: {'line': b'writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[2.434063] (robobin) StdoutLine: {'line': b'writing requirements to ../build/robobin/robobin.egg-info/requires.txt\n'}
-[2.434256] (robobin) StdoutLine: {'line': b'writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt\n'}
-[2.496287] (robobin) StdoutLine: {'line': b"reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.497917] (robobin) StdoutLine: {'line': b"writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[2.498359] (robobin) StdoutLine: {'line': b'running build\n'}
-[2.498523] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[2.499497] (robobin) StdoutLine: {'line': b'running install\n'}
-[2.512077] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[2.527849] (-) TimerEvent: {}
-[2.549569] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[2.550159] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[2.581637] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[2.584329] (robobin) StdoutLine: {'line': b'Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[2.584532] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.627968] (-) TimerEvent: {}
-[2.728554] (-) TimerEvent: {}
-[2.806295] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.806825] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.807735] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.808897] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'\n"}
-[2.828721] (-) TimerEvent: {}
-[2.923546] (robobin) CommandEnded: {'returncode': 0}
-[2.928780] (-) TimerEvent: {}
-[2.946991] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.948948] (-) EventReactorShutdown: {}
diff --git a/ros2/src/log/build_2024-12-16_16-27-14/logger_all.log b/ros2/src/log/build_2024-12-16_16-27-14/logger_all.log
deleted file mode 100644
index f064724a1f872819a552b35ecbf519c80aba2d70..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-27-14/logger_all.log
+++ /dev/null
@@ -1,114 +0,0 @@
-[0.171s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.171s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffffb3115730>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffffb3115460>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffffb3115460>>, mixin_verb=('build',))
-[0.236s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.236s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.236s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.236s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.236s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.236s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.236s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2/src'
-[0.236s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.237s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.279s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.280s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.280s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.280s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.280s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.280s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.280s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.280s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.280s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.280s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.280s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore'
-[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore_ament_install'
-[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_pkg']
-[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_pkg'
-[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_meta']
-[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_meta'
-[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ros']
-[0.281s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ros'
-[0.284s] DEBUG:colcon.colcon_core.package_identification:Package 'robobin' with type 'ros.ament_python' and name 'robobin'
-[0.284s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.284s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.284s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.284s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.284s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.313s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.313s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.317s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 1 installed packages in /home/robobin/robobin/ros2/src/install
-[0.318s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.320s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.325s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.394s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.394s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.394s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.394s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.394s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.394s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.394s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.394s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.394s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.394s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/src/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/src/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.395s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.396s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.397s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.398s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.404s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.404s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.407s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.409s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.412s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.412s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.925s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.926s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.927s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[2.300s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[3.320s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[3.324s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake module files
-[3.324s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake config files
-[3.327s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib'
-[3.328s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[3.328s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/pkgconfig/robobin.pc'
-[3.329s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages'
-[3.329s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[3.330s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.ps1'
-[3.332s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.dsv'
-[3.334s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.sh'
-[3.335s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[3.335s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[3.336s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.ps1'
-[3.337s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.dsv'
-[3.338s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.sh'
-[3.339s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.bash'
-[3.341s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.zsh'
-[3.341s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/src/install/robobin/share/colcon-core/packages/robobin)
-[3.343s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[3.344s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[3.344s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[3.344s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[3.355s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[3.356s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[3.356s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[3.384s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[3.385s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.ps1'
-[3.386s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_ps1.py'
-[3.388s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.ps1'
-[3.390s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.sh'
-[3.392s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_sh.py'
-[3.393s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.sh'
-[3.395s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.bash'
-[3.397s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.bash'
-[3.399s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.zsh'
-[3.401s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.zsh'
diff --git a/ros2/src/log/build_2024-12-16_16-27-14/robobin/command.log b/ros2/src/log/build_2024-12-16_16-27-14/robobin/command.log
deleted file mode 100644
index f3802c6a7d0396462088b5e246ef91cbbe9f914c..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-27-14/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-16_16-27-14/robobin/stderr.log b/ros2/src/log/build_2024-12-16_16-27-14/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/log/build_2024-12-16_16-27-14/robobin/stdout.log b/ros2/src/log/build_2024-12-16_16-27-14/robobin/stdout.log
deleted file mode 100644
index d35c3761dc8e2e1880738db93e9a5af0d244d95b..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-27-14/robobin/stdout.log
+++ /dev/null
@@ -1,21 +0,0 @@
-running egg_info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-running install
-running install_lib
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-16_16-27-14/robobin/stdout_stderr.log b/ros2/src/log/build_2024-12-16_16-27-14/robobin/stdout_stderr.log
deleted file mode 100644
index d35c3761dc8e2e1880738db93e9a5af0d244d95b..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-27-14/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,21 +0,0 @@
-running egg_info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-running install
-running install_lib
-running install_data
-running install_egg_info
-removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-16_16-27-14/robobin/streams.log b/ros2/src/log/build_2024-12-16_16-27-14/robobin/streams.log
deleted file mode 100644
index 226b3d1f88f143c24c504d28185314e183b4a739..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-16_16-27-14/robobin/streams.log
+++ /dev/null
@@ -1,23 +0,0 @@
-[1.902s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[2.391s] running egg_info
-[2.423s] writing ../build/robobin/robobin.egg-info/PKG-INFO
-[2.432s] writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-[2.432s] writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-[2.433s] writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-[2.433s] writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-[2.495s] reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.496s] writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[2.497s] running build
-[2.497s] running build_py
-[2.498s] running install
-[2.511s] running install_lib
-[2.548s] running install_data
-[2.549s] running install_egg_info
-[2.580s] removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[2.583s] Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[2.583s] running install_scripts
-[2.805s] Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.805s] Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.806s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.807s] writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
-[2.923s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-18_16-50-13/events.log b/ros2/src/log/build_2024-12-18_16-50-13/events.log
deleted file mode 100644
index 9be8dbd4b910b1e284ef38a1cc4c155a53a2e075..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-18_16-50-13/events.log
+++ /dev/null
@@ -1,90 +0,0 @@
-[0.000000] (-) TimerEvent: {}
-[0.000433] (robobin) JobQueued: {'identifier': 'robobin', 'dependencies': OrderedDict()}
-[0.000733] (robobin) JobStarted: {'identifier': 'robobin'}
-[0.099676] (-) TimerEvent: {}
-[0.200003] (-) TimerEvent: {}
-[0.300315] (-) TimerEvent: {}
-[0.400642] (-) TimerEvent: {}
-[0.501002] (-) TimerEvent: {}
-[0.601332] (-) TimerEvent: {}
-[0.701634] (-) TimerEvent: {}
-[0.801956] (-) TimerEvent: {}
-[0.902265] (-) TimerEvent: {}
-[1.002594] (-) TimerEvent: {}
-[1.102912] (-) TimerEvent: {}
-[1.203250] (-) TimerEvent: {}
-[1.303653] (-) TimerEvent: {}
-[1.327107] (robobin) Command: {'cmd': ['/usr/bin/python3', '-W', 'ignore:setup.py install is deprecated', '-W', 'ignore:easy_install command is deprecated', 'setup.py', 'egg_info', '--egg-base', '../build/robobin', 'build', '--build-base', '/home/robobin/robobin/ros2/src/build/robobin/build', 'install', '--record', '/home/robobin/robobin/ros2/src/build/robobin/install.log', '--single-version-externally-managed', 'install_data'], 'cwd': '/home/robobin/robobin/ros2/src/robobin', 'env': {'LESSOPEN': '| /usr/bin/lesspipe %s', 'USER': 'robobin', 'SSH_CLIENT': '192.168.73.238 47996 22', 'GZ_CONFIG_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/share/gz', 'XDG_SESSION_TYPE': 'tty', 'SHLVL': '1', 'LD_LIBRARY_PATH': '/opt/ros/jazzy/opt/sdformat_vendor/lib:/opt/ros/jazzy/opt/rviz_ogre_vendor/lib:/opt/ros/jazzy/lib/aarch64-linux-gnu:/opt/ros/jazzy/opt/gz_math_vendor/lib:/opt/ros/jazzy/opt/gz_utils_vendor/lib:/opt/ros/jazzy/opt/gz_tools_vendor/lib:/opt/ros/jazzy/opt/gz_cmake_vendor/lib:/opt/ros/jazzy/lib', 'HOME': '/home/robobin', 'OLDPWD': '/home/robobin/robobin/ros2', 'SSH_TTY': '/dev/pts/0', 'ROS_PYTHON_VERSION': '3', 'DBUS_SESSION_BUS_ADDRESS': 'unix:path=/run/user/1002/bus', 'DEBUGINFOD_URLS': 'https://debuginfod.ubuntu.com', 'COLCON_PREFIX_PATH': '/home/robobin/Robobin_Project/ros2/robobin_main/install', 'ROS_DISTRO': 'jazzy', 'LOGNAME': 'robobin', '_': '/usr/bin/colcon', 'ROS_VERSION': '2', 'XDG_SESSION_CLASS': 'user', 'TERM': 'xterm-256color', 'XDG_SESSION_ID': '4', 'PATH': '/opt/ros/jazzy/opt/gz_tools_vendor/bin:/opt/ros/jazzy/bin:/usr/local/sbin:/usr/local/bin:/usr/sbin:/usr/bin:/sbin:/bin:/usr/games:/usr/local/games:/snap/bin', 'XDG_RUNTIME_DIR': '/run/user/1002', 'LANG': 'en_US.UTF-8', 'LS_COLORS': 'rs=0:di=01;34:ln=01;36:mh=00:pi=40;33:so=01;35:do=01;35:bd=40;33;01:cd=40;33;01:or=40;31;01:mi=00:su=37;41:sg=30;43:ca=00:tw=30;42:ow=34;42:st=37;44:ex=01;32:*.tar=01;31:*.tgz=01;31:*.arc=01;31:*.arj=01;31:*.taz=01;31:*.lha=01;31:*.lz4=01;31:*.lzh=01;31:*.lzma=01;31:*.tlz=01;31:*.txz=01;31:*.tzo=01;31:*.t7z=01;31:*.zip=01;31:*.z=01;31:*.dz=01;31:*.gz=01;31:*.lrz=01;31:*.lz=01;31:*.lzo=01;31:*.xz=01;31:*.zst=01;31:*.tzst=01;31:*.bz2=01;31:*.bz=01;31:*.tbz=01;31:*.tbz2=01;31:*.tz=01;31:*.deb=01;31:*.rpm=01;31:*.jar=01;31:*.war=01;31:*.ear=01;31:*.sar=01;31:*.rar=01;31:*.alz=01;31:*.ace=01;31:*.zoo=01;31:*.cpio=01;31:*.7z=01;31:*.rz=01;31:*.cab=01;31:*.wim=01;31:*.swm=01;31:*.dwm=01;31:*.esd=01;31:*.avif=01;35:*.jpg=01;35:*.jpeg=01;35:*.mjpg=01;35:*.mjpeg=01;35:*.gif=01;35:*.bmp=01;35:*.pbm=01;35:*.pgm=01;35:*.ppm=01;35:*.tga=01;35:*.xbm=01;35:*.xpm=01;35:*.tif=01;35:*.tiff=01;35:*.png=01;35:*.svg=01;35:*.svgz=01;35:*.mng=01;35:*.pcx=01;35:*.mov=01;35:*.mpg=01;35:*.mpeg=01;35:*.m2v=01;35:*.mkv=01;35:*.webm=01;35:*.webp=01;35:*.ogm=01;35:*.mp4=01;35:*.m4v=01;35:*.mp4v=01;35:*.vob=01;35:*.qt=01;35:*.nuv=01;35:*.wmv=01;35:*.asf=01;35:*.rm=01;35:*.rmvb=01;35:*.flc=01;35:*.avi=01;35:*.fli=01;35:*.flv=01;35:*.gl=01;35:*.dl=01;35:*.xcf=01;35:*.xwd=01;35:*.yuv=01;35:*.cgm=01;35:*.emf=01;35:*.ogv=01;35:*.ogx=01;35:*.aac=00;36:*.au=00;36:*.flac=00;36:*.m4a=00;36:*.mid=00;36:*.midi=00;36:*.mka=00;36:*.mp3=00;36:*.mpc=00;36:*.ogg=00;36:*.ra=00;36:*.wav=00;36:*.oga=00;36:*.opus=00;36:*.spx=00;36:*.xspf=00;36:*~=00;90:*#=00;90:*.bak=00;90:*.crdownload=00;90:*.dpkg-dist=00;90:*.dpkg-new=00;90:*.dpkg-old=00;90:*.dpkg-tmp=00;90:*.old=00;90:*.orig=00;90:*.part=00;90:*.rej=00;90:*.rpmnew=00;90:*.rpmorig=00;90:*.rpmsave=00;90:*.swp=00;90:*.tmp=00;90:*.ucf-dist=00;90:*.ucf-new=00;90:*.ucf-old=00;90:', 'ROS_DOMAIN_ID': '3', 'AMENT_PREFIX_PATH': '/home/robobin/Robobin_Project/ros2/robobin_main/install/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher:/opt/ros/jazzy', 'SHELL': '/bin/bash', 'LESSCLOSE': '/usr/bin/lesspipe %s %s', 'ROS_AUTOMATIC_DISCOVERY_RANGE': 'SUBNET', 'PWD': '/home/robobin/robobin/ros2/src/build/robobin', 'LC_ALL': 'en_US.UTF-8', 'SSH_CONNECTION': '192.168.73.238 47996 192.168.73.109 22', 'XDG_DATA_DIRS': '/usr/share/gnome:/usr/local/share:/usr/share:/var/lib/snapd/desktop', 'PYTHONPATH': '/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/testing:/home/robobin/Robobin_Project/ros2/robobin_main/install/testing/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_localization_ekf:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_localization_ekf/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/robot_description:/home/robobin/Robobin_Project/ros2/robobin_main/install/robot_description/lib/python3.12/site-packages:/home/robobin/Robobin_Project/ros2/robobin_main/build/odometry_publisher:/home/robobin/Robobin_Project/ros2/robobin_main/install/odometry_publisher/lib/python3.12/site-packages:/opt/ros/jazzy/lib/python3.12/site-packages', 'COLCON': '1', 'CMAKE_PREFIX_PATH': '/opt/ros/jazzy/opt/sdformat_vendor:/opt/ros/jazzy/opt/gz_math_vendor:/opt/ros/jazzy/opt/gz_utils_vendor:/opt/ros/jazzy/opt/gz_tools_vendor:/opt/ros/jazzy/opt/gz_cmake_vendor'}, 'shell': False}
-[1.403754] (-) TimerEvent: {}
-[1.504078] (-) TimerEvent: {}
-[1.604376] (-) TimerEvent: {}
-[1.704679] (-) TimerEvent: {}
-[1.730299] (robobin) StdoutLine: {'line': b'running egg_info\n'}
-[1.758749] (robobin) StdoutLine: {'line': b'writing ../build/robobin/robobin.egg-info/PKG-INFO\n'}
-[1.759920] (robobin) StdoutLine: {'line': b'writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt\n'}
-[1.760776] (robobin) StdoutLine: {'line': b'writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt\n'}
-[1.761301] (robobin) StdoutLine: {'line': b'writing requirements to ../build/robobin/robobin.egg-info/requires.txt\n'}
-[1.762038] (robobin) StdoutLine: {'line': b'writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt\n'}
-[1.804778] (-) TimerEvent: {}
-[1.820766] (robobin) StdoutLine: {'line': b"reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.822555] (robobin) StdoutLine: {'line': b"writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'\n"}
-[1.822838] (robobin) StdoutLine: {'line': b'running build\n'}
-[1.823003] (robobin) StdoutLine: {'line': b'running build_py\n'}
-[1.824588] (robobin) StdoutLine: {'line': b'copying robobin/encoder.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[1.825629] (robobin) StdoutLine: {'line': b'copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[1.826704] (robobin) StdoutLine: {'line': b'copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[1.827795] (robobin) StdoutLine: {'line': b'copying robobin/imu_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[1.828341] (robobin) StdoutLine: {'line': b'copying robobin/api_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[1.829029] (robobin) StdoutLine: {'line': b'copying robobin/control_feedback.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[1.829762] (robobin) StdoutLine: {'line': b'copying robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin\n'}
-[1.830892] (robobin) StdoutLine: {'line': b'copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers\n'}
-[1.831808] (robobin) StdoutLine: {'line': b'copying robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers\n'}
-[1.833133] (robobin) StdoutLine: {'line': b'copying robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers\n'}
-[1.833671] (robobin) StdoutLine: {'line': b'copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers\n'}
-[1.834596] (robobin) StdoutLine: {'line': b'running install\n'}
-[1.846393] (robobin) StdoutLine: {'line': b'running install_lib\n'}
-[1.876276] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/encoder.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.876746] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.877142] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.877842] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.878132] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.878310] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.878482] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers\n'}
-[1.878667] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/imu_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.878825] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.879043] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/control_feedback.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.879195] (robobin) StdoutLine: {'line': b'copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin\n'}
-[1.880461] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/encoder.py to encoder.cpython-312.pyc\n'}
-[1.881447] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc\n'}
-[1.882794] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc\n'}
-[1.892355] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc\n'}
-[1.895437] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py to realtime_location_cli_only.cpython-312.pyc\n'}
-[1.898821] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py to graph_maker.cpython-312.pyc\n'}
-[1.900384] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc\n'}
-[1.901846] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py to imu_node.cpython-312.pyc\n'}
-[1.903227] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc\n'}
-[1.904836] (-) TimerEvent: {}
-[1.905988] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py to control_feedback.cpython-312.pyc\n'}
-[1.908762] (robobin) StdoutLine: {'line': b'byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py to uwb_pathing_node.cpython-312.pyc\n'}
-[1.911033] (robobin) StdoutLine: {'line': b'running install_data\n'}
-[1.912619] (robobin) StdoutLine: {'line': b'copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch\n'}
-[1.913357] (robobin) StdoutLine: {'line': b'copying launch/robobin_no_components_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch\n'}
-[1.913928] (robobin) StdoutLine: {'line': b'running install_egg_info\n'}
-[1.945874] (robobin) StdoutLine: {'line': b"removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)\n"}
-[1.946321] (robobin) StdoutLine: {'line': b'Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info\n'}
-[1.948168] (robobin) StdoutLine: {'line': b'running install_scripts\n'}
-[2.004956] (-) TimerEvent: {}
-[2.105279] (-) TimerEvent: {}
-[2.151850] (robobin) StdoutLine: {'line': b'Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.152620] (robobin) StdoutLine: {'line': b'Installing control_feedback script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.152821] (robobin) StdoutLine: {'line': b'Installing encoder_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.152981] (robobin) StdoutLine: {'line': b'Installing imu_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.153123] (robobin) StdoutLine: {'line': b'Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.153820] (robobin) StdoutLine: {'line': b'Installing motor_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.153967] (robobin) StdoutLine: {'line': b'Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.155244] (robobin) StdoutLine: {'line': b'Installing uwb_pathing_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin\n'}
-[2.155916] (robobin) StdoutLine: {'line': b"writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'\n"}
-[2.205421] (-) TimerEvent: {}
-[2.249328] (robobin) CommandEnded: {'returncode': 0}
-[2.268912] (robobin) JobEnded: {'identifier': 'robobin', 'rc': 0}
-[2.270060] (-) EventReactorShutdown: {}
diff --git a/ros2/src/log/build_2024-12-18_16-50-13/logger_all.log b/ros2/src/log/build_2024-12-18_16-50-13/logger_all.log
deleted file mode 100644
index df5c3d20afa5c7f778bf31f3736b8a7336dcb776..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-18_16-50-13/logger_all.log
+++ /dev/null
@@ -1,113 +0,0 @@
-[0.172s] DEBUG:colcon:Command line arguments: ['/usr/bin/colcon', 'build']
-[0.172s] DEBUG:colcon:Parsed command line arguments: Namespace(log_base=None, log_level=None, verb_name='build', build_base='build', install_base='install', merge_install=False, symlink_install=False, test_result_base=None, continue_on_error=False, executor='parallel', parallel_workers=4, event_handlers=None, ignore_user_meta=False, metas=['./colcon.meta'], base_paths=['.'], packages_ignore=None, packages_ignore_regex=None, paths=None, packages_up_to=None, packages_up_to_regex=None, packages_above=None, packages_above_and_dependencies=None, packages_above_depth=None, packages_select_by_dep=None, packages_skip_by_dep=None, packages_skip_up_to=None, packages_select_build_failed=False, packages_skip_build_finished=False, packages_select_test_failures=False, packages_skip_test_passed=False, packages_select=None, packages_skip=None, packages_select_regex=None, packages_skip_regex=None, packages_start=None, packages_end=None, allow_overriding=[], cmake_args=None, cmake_target=None, cmake_target_skip_unavailable=False, cmake_clean_cache=False, cmake_clean_first=False, cmake_force_configure=False, ament_cmake_args=None, catkin_cmake_args=None, catkin_skip_building_tests=False, mixin_files=None, mixin=None, verb_parser=<colcon_mixin.mixin.mixin_argument.MixinArgumentDecorator object at 0xffffa9f14e00>, verb_extension=<colcon_core.verb.build.BuildVerb object at 0xffffa9f148c0>, main=<bound method BuildVerb.main of <colcon_core.verb.build.BuildVerb object at 0xffffa9f148c0>>, mixin_verb=('build',))
-[0.238s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) check parameters
-[0.238s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) check parameters
-[0.238s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) check parameters
-[0.238s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) check parameters
-[0.238s] Level 1:colcon.colcon_core.package_discovery:discover_packages(colcon_meta) discover
-[0.238s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) discover
-[0.238s] INFO:colcon.colcon_core.package_discovery:Crawling recursively for packages in '/home/robobin/robobin/ros2/src'
-[0.238s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ignore', 'ignore_ament_install']
-[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore'
-[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ignore_ament_install'
-[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_pkg']
-[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_pkg'
-[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['colcon_meta']
-[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'colcon_meta'
-[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['ros']
-[0.239s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'ros'
-[0.285s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['cmake', 'python']
-[0.285s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'cmake'
-[0.285s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python'
-[0.285s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extensions ['python_setup_py']
-[0.285s] Level 1:colcon.colcon_core.package_identification:_identify(.) by extension 'python_setup_py'
-[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extensions ['ignore', 'ignore_ament_install']
-[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(build) by extension 'ignore'
-[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(build) ignored
-[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extensions ['ignore', 'ignore_ament_install']
-[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(install) by extension 'ignore'
-[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(install) ignored
-[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extensions ['ignore', 'ignore_ament_install']
-[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(log) by extension 'ignore'
-[0.286s] Level 1:colcon.colcon_core.package_identification:_identify(log) ignored
-[0.287s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ignore', 'ignore_ament_install']
-[0.287s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore'
-[0.287s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ignore_ament_install'
-[0.287s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_pkg']
-[0.287s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_pkg'
-[0.287s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['colcon_meta']
-[0.287s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'colcon_meta'
-[0.287s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extensions ['ros']
-[0.287s] Level 1:colcon.colcon_core.package_identification:_identify(robobin) by extension 'ros'
-[0.291s] DEBUG:colcon.colcon_core.package_identification:Package 'robobin' with type 'ros.ament_python' and name 'robobin'
-[0.291s] Level 1:colcon.colcon_core.package_discovery:discover_packages(recursive) using defaults
-[0.291s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) discover
-[0.291s] Level 1:colcon.colcon_core.package_discovery:discover_packages(ignore) using defaults
-[0.291s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) discover
-[0.291s] Level 1:colcon.colcon_core.package_discovery:discover_packages(path) using defaults
-[0.319s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) check parameters
-[0.319s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) discover
-[0.321s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 4 installed packages in /home/robobin/Robobin_Project/ros2/robobin_main/install
-[0.324s] DEBUG:colcon.colcon_installed_package_information.package_discovery:Found 335 installed packages in /opt/ros/jazzy
-[0.328s] Level 1:colcon.colcon_core.package_discovery:discover_packages(prefix_path) using defaults
-[0.400s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_args' from command line to 'None'
-[0.400s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target' from command line to 'None'
-[0.400s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_target_skip_unavailable' from command line to 'False'
-[0.400s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_cache' from command line to 'False'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_clean_first' from command line to 'False'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'cmake_force_configure' from command line to 'False'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'ament_cmake_args' from command line to 'None'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_cmake_args' from command line to 'None'
-[0.401s] Level 5:colcon.colcon_core.verb:set package 'robobin' build argument 'catkin_skip_building_tests' from command line to 'False'
-[0.401s] DEBUG:colcon.colcon_core.verb:Building package 'robobin' with the following arguments: {'ament_cmake_args': None, 'build_base': '/home/robobin/robobin/ros2/src/build/robobin', 'catkin_cmake_args': None, 'catkin_skip_building_tests': False, 'cmake_args': None, 'cmake_clean_cache': False, 'cmake_clean_first': False, 'cmake_force_configure': False, 'cmake_target': None, 'cmake_target_skip_unavailable': False, 'install_base': '/home/robobin/robobin/ros2/src/install/robobin', 'merge_install': False, 'path': '/home/robobin/robobin/ros2/src/robobin', 'symlink_install': False, 'test_result_base': None}
-[0.401s] INFO:colcon.colcon_core.executor:Executing jobs using 'parallel' executor
-[0.402s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete
-[0.403s] INFO:colcon.colcon_ros.task.ament_python.build:Building ROS package in '/home/robobin/robobin/ros2/src/robobin' with build type 'ament_python'
-[0.403s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'ament_prefix_path')
-[0.405s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_core.shell.bat': Not used on non-Windows systems
-[0.405s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.ps1'
-[0.408s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.dsv'
-[0.409s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/ament_prefix_path.sh'
-[0.410s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.410s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[0.779s] INFO:colcon.colcon_core.task.python.build:Building Python package in '/home/robobin/robobin/ros2/src/robobin'
-[0.780s] INFO:colcon.colcon_core.shell:Skip shell extension 'powershell' for command environment: Not usable outside of PowerShell
-[0.780s] DEBUG:colcon.colcon_core.shell:Skip shell extension 'dsv' for command environment
-[1.732s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[2.652s] DEBUG:colcon.colcon_core.event_handler.log_command:Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[2.654s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake module files
-[2.655s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin' for CMake config files
-[2.657s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib'
-[2.657s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[2.658s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/pkgconfig/robobin.pc'
-[2.658s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages'
-[2.658s] Level 1:colcon.colcon_core.shell:create_environment_hook('robobin', 'pythonpath')
-[2.659s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.ps1'
-[2.659s] INFO:colcon.colcon_core.shell:Creating environment descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.dsv'
-[2.660s] INFO:colcon.colcon_core.shell:Creating environment hook '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/hook/pythonpath.sh'
-[2.662s] Level 1:colcon.colcon_core.environment:checking '/home/robobin/robobin/ros2/src/install/robobin/bin'
-[2.662s] Level 1:colcon.colcon_core.environment:create_environment_scripts_only(robobin)
-[2.663s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.ps1'
-[2.664s] INFO:colcon.colcon_core.shell:Creating package descriptor '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.dsv'
-[2.666s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.sh'
-[2.667s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.bash'
-[2.668s] INFO:colcon.colcon_core.shell:Creating package script '/home/robobin/robobin/ros2/src/install/robobin/share/robobin/package.zsh'
-[2.669s] Level 1:colcon.colcon_core.environment:create_file_with_runtime_dependencies(/home/robobin/robobin/ros2/src/install/robobin/share/colcon-core/packages/robobin)
-[2.671s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:closing loop
-[2.671s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:loop closed
-[2.672s] DEBUG:colcon.colcon_parallel_executor.executor.parallel:run_until_complete finished with '0'
-[2.672s] DEBUG:colcon.colcon_core.event_reactor:joining thread
-[2.681s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.terminal_notifier': Not used on non-Darwin systems
-[2.682s] INFO:colcon.colcon_core.plugin_system:Skipping extension 'colcon_notification.desktop_notification.win32': Not used on non-Windows systems
-[2.682s] INFO:colcon.colcon_notification.desktop_notification:Sending desktop notification using 'notify2'
-[2.700s] DEBUG:colcon.colcon_core.event_reactor:joined thread
-[2.700s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.ps1'
-[2.702s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_ps1.py'
-[2.704s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.ps1'
-[2.706s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.sh'
-[2.708s] INFO:colcon.colcon_core.shell:Creating prefix util module '/home/robobin/robobin/ros2/src/install/_local_setup_util_sh.py'
-[2.709s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.sh'
-[2.712s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.bash'
-[2.715s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.bash'
-[2.716s] INFO:colcon.colcon_core.shell:Creating prefix script '/home/robobin/robobin/ros2/src/install/local_setup.zsh'
-[2.718s] INFO:colcon.colcon_core.shell:Creating prefix chain script '/home/robobin/robobin/ros2/src/install/setup.zsh'
diff --git a/ros2/src/log/build_2024-12-18_16-50-13/robobin/command.log b/ros2/src/log/build_2024-12-18_16-50-13/robobin/command.log
deleted file mode 100644
index f3802c6a7d0396462088b5e246ef91cbbe9f914c..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-18_16-50-13/robobin/command.log
+++ /dev/null
@@ -1,2 +0,0 @@
-Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/build_2024-12-18_16-50-13/robobin/stderr.log b/ros2/src/log/build_2024-12-18_16-50-13/robobin/stderr.log
deleted file mode 100644
index e69de29bb2d1d6434b8b29ae775ad8c2e48c5391..0000000000000000000000000000000000000000
diff --git a/ros2/src/log/build_2024-12-18_16-50-13/robobin/stdout.log b/ros2/src/log/build_2024-12-18_16-50-13/robobin/stdout.log
deleted file mode 100644
index c4f70284cee6d418c4648eb65c081a6ea5f10826..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-18_16-50-13/robobin/stdout.log
+++ /dev/null
@@ -1,61 +0,0 @@
-running egg_info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/encoder.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/imu_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/api_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/control_feedback.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/encoder.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/imu_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/control_feedback.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/encoder.py to encoder.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py to realtime_location_cli_only.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py to graph_maker.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py to imu_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py to control_feedback.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py to uwb_pathing_node.cpython-312.pyc
-running install_data
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-copying launch/robobin_no_components_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-running install_egg_info
-removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing control_feedback script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing encoder_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing imu_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_pathing_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-18_16-50-13/robobin/stdout_stderr.log b/ros2/src/log/build_2024-12-18_16-50-13/robobin/stdout_stderr.log
deleted file mode 100644
index c4f70284cee6d418c4648eb65c081a6ea5f10826..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-18_16-50-13/robobin/stdout_stderr.log
+++ /dev/null
@@ -1,61 +0,0 @@
-running egg_info
-writing ../build/robobin/robobin.egg-info/PKG-INFO
-writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-running build
-running build_py
-copying robobin/encoder.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/imu_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/api_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/control_feedback.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-running install
-running install_lib
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/encoder.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/imu_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/control_feedback.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/encoder.py to encoder.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py to realtime_location_cli_only.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py to graph_maker.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py to imu_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py to control_feedback.cpython-312.pyc
-byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py to uwb_pathing_node.cpython-312.pyc
-running install_data
-copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-copying launch/robobin_no_components_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-running install_egg_info
-removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-running install_scripts
-Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing control_feedback script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing encoder_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing imu_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing motor_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-Installing uwb_pathing_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
diff --git a/ros2/src/log/build_2024-12-18_16-50-13/robobin/streams.log b/ros2/src/log/build_2024-12-18_16-50-13/robobin/streams.log
deleted file mode 100644
index d33cf71f4f9f185c4cfc882bcc410d5ea5fa89c2..0000000000000000000000000000000000000000
--- a/ros2/src/log/build_2024-12-18_16-50-13/robobin/streams.log
+++ /dev/null
@@ -1,63 +0,0 @@
-[1.329s] Invoking command in '/home/robobin/robobin/ros2/src/robobin': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
-[1.730s] running egg_info
-[1.758s] writing ../build/robobin/robobin.egg-info/PKG-INFO
-[1.759s] writing dependency_links to ../build/robobin/robobin.egg-info/dependency_links.txt
-[1.760s] writing entry points to ../build/robobin/robobin.egg-info/entry_points.txt
-[1.761s] writing requirements to ../build/robobin/robobin.egg-info/requires.txt
-[1.761s] writing top-level names to ../build/robobin/robobin.egg-info/top_level.txt
-[1.820s] reading manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.822s] writing manifest file '../build/robobin/robobin.egg-info/SOURCES.txt'
-[1.822s] running build
-[1.822s] running build_py
-[1.824s] copying robobin/encoder.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[1.825s] copying robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[1.826s] copying robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[1.827s] copying robobin/imu_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[1.828s] copying robobin/api_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[1.828s] copying robobin/control_feedback.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[1.829s] copying robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin
-[1.830s] copying robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-[1.831s] copying robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-[1.832s] copying robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-[1.833s] copying robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers
-[1.834s] running install
-[1.846s] running install_lib
-[1.876s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/encoder.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[1.876s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/motor_control_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[1.876s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_navigation_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[1.877s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/message_handler.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.877s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/realtime_location_cli_only.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.878s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/graph_maker.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.878s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/helpers/connection_manager.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers
-[1.878s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/imu_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[1.878s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/api_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[1.878s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/control_feedback.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[1.879s] copying /home/robobin/robobin/ros2/src/build/robobin/build/lib/robobin/uwb_pathing_node.py -> /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin
-[1.880s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/encoder.py to encoder.cpython-312.pyc
-[1.881s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/motor_control_node.py to motor_control_node.cpython-312.pyc
-[1.882s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_navigation_node.py to uwb_navigation_node.cpython-312.pyc
-[1.892s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/message_handler.py to message_handler.cpython-312.pyc
-[1.895s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/realtime_location_cli_only.py to realtime_location_cli_only.cpython-312.pyc
-[1.898s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/graph_maker.py to graph_maker.cpython-312.pyc
-[1.900s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/helpers/connection_manager.py to connection_manager.cpython-312.pyc
-[1.901s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/imu_node.py to imu_node.cpython-312.pyc
-[1.903s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/api_node.py to api_node.cpython-312.pyc
-[1.905s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/control_feedback.py to control_feedback.cpython-312.pyc
-[1.908s] byte-compiling /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin/uwb_pathing_node.py to uwb_pathing_node.cpython-312.pyc
-[1.910s] running install_data
-[1.912s] copying launch/robobin_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-[1.913s] copying launch/robobin_no_components_launch.py -> /home/robobin/robobin/ros2/src/install/robobin/share/robobin/launch
-[1.913s] running install_egg_info
-[1.945s] removing '/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info' (and everything under it)
-[1.946s] Copying ../build/robobin/robobin.egg-info to /home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages/robobin-0.0.0-py3.12.egg-info
-[1.948s] running install_scripts
-[2.151s] Installing api_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.152s] Installing control_feedback script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.152s] Installing encoder_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.152s] Installing imu_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.152s] Installing motor_control_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.153s] Installing motor_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.153s] Installing uwb_navigation_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.155s] Installing uwb_pathing_node script to /home/robobin/robobin/ros2/src/install/robobin/lib/robobin
-[2.155s] writing list of installed files to '/home/robobin/robobin/ros2/src/build/robobin/install.log'
-[2.249s] Invoked command in '/home/robobin/robobin/ros2/src/robobin' returned '0': DEBUGINFOD_URLS=https://debuginfod.ubuntu.com PYTHONPATH=/home/robobin/robobin/ros2/src/build/robobin/prefix_override:/usr/lib/python3/dist-packages/colcon_core/task/python/colcon_distutils_commands:/home/robobin/robobin/ros2/src/install/robobin/lib/python3.12/site-packages:${PYTHONPATH} /usr/bin/python3 -W ignore:setup.py install is deprecated -W ignore:easy_install command is deprecated setup.py egg_info --egg-base ../build/robobin build --build-base /home/robobin/robobin/ros2/src/build/robobin/build install --record /home/robobin/robobin/ros2/src/build/robobin/install.log --single-version-externally-managed install_data
diff --git a/ros2/src/log/latest b/ros2/src/log/latest
deleted file mode 120000
index b57d247c77c0293269460b70b9bb1360f27cf808..0000000000000000000000000000000000000000
--- a/ros2/src/log/latest
+++ /dev/null
@@ -1 +0,0 @@
-latest_build
\ No newline at end of file
diff --git a/ros2/src/log/latest_build b/ros2/src/log/latest_build
deleted file mode 120000
index 8017e47ab26bf68df1d48ca7bdbab5b1ae6cf18b..0000000000000000000000000000000000000000
--- a/ros2/src/log/latest_build
+++ /dev/null
@@ -1 +0,0 @@
-build_2024-12-16_16-27-14
\ No newline at end of file