diff --git a/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp b/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp index 141988c92d29c7aa756b33f64f19cc80d5eb773c..54c03de049dc4a9ee43a9161bbdd70a8f2c8fc4b 100644 --- a/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp +++ b/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp @@ -26,17 +26,12 @@ void Ultrasonic::onInit() main = boost::thread( [this]() { - ros::Rate rate{1}; - while (ros::ok()) + for (;;) { ussDataMsg msg; auto distance = getDistance(); msg.distance = distance; - std::cout << "\n------------------------\n" - << "distance: " << distance - << "\n------------------------\n\n"; ussData.publish(msg); - rate.sleep(); } });