diff --git a/omnidrive_rppico/hardware/include/omnidrive_rppico/rppico_comms.hpp b/omnidrive_rppico/hardware/include/omnidrive_rppico/rppico_comms.hpp
index 678997a..97b03ad 100644
--- a/omnidrive_rppico/hardware/include/omnidrive_rppico/rppico_comms.hpp
+++ b/omnidrive_rppico/hardware/include/omnidrive_rppico/rppico_comms.hpp
@@ -39,6 +39,7 @@ class RpPicoComs
void connect(const std::string &serial_device, int32_t baud_rate, int32_t timeout_ms)
{
+ std::cout << "Connecting to serial device: " << serial_device << " at baud rate: " << baud_rate << std::endl;
timeout_ms_ = timeout_ms;
serial_conn_.Open(serial_device);
serial_conn_.SetBaudRate(convert_baud_rate(baud_rate));
diff --git a/src/ezbot_robot/description/ros2_control.xacro b/src/ezbot_robot/description/ros2_control.xacro
index 01e9c1f..9ef8cf0 100644
--- a/src/ezbot_robot/description/ros2_control.xacro
+++ b/src/ezbot_robot/description/ros2_control.xacro
@@ -11,7 +11,7 @@
roue_arriere_joint
roue_droite_joint
- 30.0
+ 30
/dev/ttyAMA1
115200