diff --git a/depthai_ros_driver/src/camera.cpp b/depthai_ros_driver/src/camera.cpp index 2773cb08..b4900965 100644 --- a/depthai_ros_driver/src/camera.cpp +++ b/depthai_ros_driver/src/camera.cpp @@ -165,8 +165,7 @@ void Camera::startDevice() { throw std::runtime_error("Device is already booted in different process."); } } else { - RCLCPP_INFO(this->get_logger(), "Device info: MXID: %s, Name: %s", info.getMxId().c_str(), info.name.c_str()); - throw std::runtime_error("Unable to connect to the device, check if parameters match with given info."); + RCLCPP_INFO(this->get_logger(), "Ignoring device info: MXID: %s, Name: %s", info.getMxId().c_str(), info.name.c_str()); } } }