diff --git a/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp b/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp index 0f4ed51933b1d91eca75502bfe263ce525685922..bea3ccadc0061dabe8204c8cca8017bf47b62caa 100644 --- a/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp +++ b/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp @@ -21,19 +21,16 @@ Ultrasonic::~Ultrasonic() void Ultrasonic::onInit() { - int dist = getDistance(); - NODELET_INFO("Ultrasonic::onInit -- START"); ussData = nh_.advertise<ussDataMsg>("ussData", 1); main = boost::thread( [this]() { - int counter = 0; ros::Rate rate{1}; while (ros::ok()) { ussDataMsg msg; - msg.distance = counter++; + msg.distance = getDistance(); ussData.publish(msg); rate.sleep(); }