diff --git a/pcl_ros/tools/pcd_to_pointcloud.cpp b/pcl_ros/tools/pcd_to_pointcloud.cpp index 655b4341..03638183 100644 --- a/pcl_ros/tools/pcd_to_pointcloud.cpp +++ b/pcl_ros/tools/pcd_to_pointcloud.cpp @@ -43,6 +43,10 @@ **/ +// STL +#include +#include + // ROS core #include #include @@ -116,7 +120,7 @@ class PCDGenerator continue; } - usleep (interval); + std::this_thread::sleep_for(std::chrono::microseconds(static_cast(interval))); if (interval == 0) // We only publish once if a 0 seconds interval is given {