diff --git a/ros2/src/robobin/robobin/api_node.py b/ros2/src/robobin/robobin/api_node.py
index db8b13fac56e695949e75f43d61b58ac14d4bcba..e682d2ce07909ab9aabc20a7e0ee23a7d3815fc2 100644
--- a/ros2/src/robobin/robobin/api_node.py
+++ b/ros2/src/robobin/robobin/api_node.py
@@ -33,8 +33,10 @@ class ApiNode(Node):
                 data = client_socket.recv(1024).decode()
                 if not data:
                     break
+                self.api_node.get_logger().info(f"Received data: {data}")
                 topic,message = self.message_handler.handle_message(client_socket, data)
                 if topic is not None:
+                    self.api_node.get_logger().info(f"Publishing to topic: {topic}")
                     self.publish_to_topic(topic, message)
         finally:
             client_socket.close()
diff --git a/ros2/src/robobin/robobin/connection_manager.py b/ros2/src/robobin/robobin/connection_manager.py
index e7e106c0fb7c37512194be52a4cfda59a6afe090..b30d5d2bc8a09464bce8daf07953d3021cdca224 100644
--- a/ros2/src/robobin/robobin/connection_manager.py
+++ b/ros2/src/robobin/robobin/connection_manager.py
@@ -28,13 +28,13 @@ class ConnectionManager:
             try:
                 data, addr = udp_sock.recvfrom(1024)
                 if data.decode() == "CONNECT":
-                    print(f"Connection request from {addr}")
+                    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()
-                    print(f"Client connected from {client_addr}")
+                    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
@@ -54,13 +54,13 @@ class ConnectionManager:
                 location = "(0,0)" #At some point this will be retrieved from navigation node
                 message = f"ROBOBIN_PRESENT {location}".encode()
                 sock.sendto(message, (self.UDP_IP, self.UDP_PORT))
-                print("Broadcasting presence.")
+                self.api_node.get_logger().info("Broadcasting presence.")
                 time.sleep(5)
             except OSError:
                 break
 
         sock.close()
-        print("Stopped broadcasting presence.")
+        self.api_node.get_logger().info("Stopped broadcasting presence.")
 
     def stop(self):
         """Stops the connection manager."""