diff --git a/modules/catkin_ws/src/car/CMakeLists.txt b/modules/catkin_ws/src/car/CMakeLists.txt index a3da590db6455e6b9b968d8ae1c71e850b6f19b5..9d7ff7fcfa2294b017004a857b9ad97a56cdebf2 100644 --- a/modules/catkin_ws/src/car/CMakeLists.txt +++ b/modules/catkin_ws/src/car/CMakeLists.txt @@ -150,8 +150,11 @@ add_library(ultrasonic ${USS_SOURCE_FILES}) add_dependencies(ultrasonic ${catkin_EXPORTED_TARGETS} ${PROJECT_NAME}_generate_messages_cpp) target_link_libraries(ultrasonic ${catkin_LIBRARIES} - libwiringPi.so -) + NetworkingLib + libwiringPi.so) +target_include_directories(ultrasonic PUBLIC + ${NetworkingLib_INCLUDE_DIRS} + ${MessageLib_INCLUDE_DIRS}) find_package( OpenCV REQUIRED ) add_library(camera ${CAMERA_SOURCE_FILES}) diff --git a/modules/catkin_ws/src/car/include/ultrasonic/Ultrasonic.h b/modules/catkin_ws/src/car/include/ultrasonic/Ultrasonic.h index 4c5c900ac30f0efab5f6c5b04ca04f57b7320be2..d8d2022787b2116004a4b7accd63dd0d2985dfa4 100644 --- a/modules/catkin_ws/src/car/include/ultrasonic/Ultrasonic.h +++ b/modules/catkin_ws/src/car/include/ultrasonic/Ultrasonic.h @@ -8,6 +8,7 @@ #include "StreamMedianFilter.h" #include <thread> #include <logging/MessageOStream.h> +#include "NetworkingLib/Timer.h" namespace car { @@ -25,7 +26,8 @@ private: ros::Publisher ussData; UltrasonicSensor sensor; StreamMedianFilter streamMedianFilter; - std::thread sensorThread; + networking::Networking net; + networking::time::Timer::Ptr timer; }; } diff --git a/modules/catkin_ws/src/car/include/ultrasonic/UltrasonicSensor.h b/modules/catkin_ws/src/car/include/ultrasonic/UltrasonicSensor.h index 7d1711a658e33dee1bce8e7ec732af74e554bfe4..8150e3556bed49703669b78db137529548068672 100644 --- a/modules/catkin_ws/src/car/include/ultrasonic/UltrasonicSensor.h +++ b/modules/catkin_ws/src/car/include/ultrasonic/UltrasonicSensor.h @@ -21,7 +21,7 @@ public: static constexpr int RESULT_LOW_BYTE = 0x03; static constexpr int RANGING_MODE_CM = 0x51; - static constexpr int DELAY = 10; //70 ms for ranging to finish + static constexpr int DELAY = 70; //70 ms for ranging to finish static constexpr int MAX_DISTANCE = 255; diff --git a/modules/catkin_ws/src/car/msg/ussDataMsg.msg b/modules/catkin_ws/src/car/msg/ussDataMsg.msg index 5cd4939c331527d5422b2fedc60172f7fde80262..5d17d4de8fa32a621567fd8a22f9ca98d7b1c64f 100644 --- a/modules/catkin_ws/src/car/msg/ussDataMsg.msg +++ b/modules/catkin_ws/src/car/msg/ussDataMsg.msg @@ -1 +1,2 @@ float32 distance +time timestamp diff --git a/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp b/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp index 4de34f010ad532abf38d832b2e6c4dbc91885616..847e7b1757f923de43974c8233c05e81e2badf24 100644 --- a/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp +++ b/modules/catkin_ws/src/car/src/ultrasonic/Ultrasonic.cpp @@ -23,18 +23,19 @@ void Ultrasonic::onInit() ussData = nh.advertise<ussDataMsg>("ussData", 1); sensor.init(); - sensorThread = std::thread{ - [this] + timer = networking::time::Timer::create(net); + timer->startPeriodicTimeout( + std::chrono::milliseconds(UltrasonicSensor::DELAY), + [&] { - for (;;) - { - ussDataMsg msg; - auto distance = streamMedianFilter.moveWindow(sensor.getDistance()); - msg.distance = distance; - ussData.publish(msg); - } - }}; + ussDataMsg msg; + auto distance = streamMedianFilter.moveWindow(sensor.getDistance()); + msg.distance = distance; + msg.timestamp = ros::Time::now(); + ussData.publish(msg); + }); messageOStream.write("onInit", "END"); } + } diff --git a/modules/catkin_ws/src/car/src/ultrasonic/UltrasonicSensor.cpp b/modules/catkin_ws/src/car/src/ultrasonic/UltrasonicSensor.cpp index 266fa48976a743290de8d3e06b13eeb9d3118f30..f61a60139d2e05b5584b92e0ee26a7efd07d4a8c 100644 --- a/modules/catkin_ws/src/car/src/ultrasonic/UltrasonicSensor.cpp +++ b/modules/catkin_ws/src/car/src/ultrasonic/UltrasonicSensor.cpp @@ -36,7 +36,6 @@ int UltrasonicSensor::getDistance() throw std::runtime_error{"Sensor not initialized!\n"}; wiringPiI2CWriteReg8(fd, COMMAND_REGISTER, RANGING_MODE_CM); - usleep(DELAY * 1000); int distance = wiringPiI2CReadReg16(fd, RESULT_LOW_BYTE); if (distance == 0) // 0 means distance too far distance = 255;