From c3748488f4a2c4f110f9dd331b1cc9628260df8f Mon Sep 17 00:00:00 2001 From: Tobias Fischer Date: Fri, 3 Jan 2025 16:07:55 +1000 Subject: [PATCH] Update ros-noetic-topic-tools.patch --- patch/ros-noetic-topic-tools.patch | 20 ++++++++++++++------ 1 file changed, 14 insertions(+), 6 deletions(-) diff --git a/patch/ros-noetic-topic-tools.patch b/patch/ros-noetic-topic-tools.patch index 65b69438f..2b570ce70 100644 --- a/patch/ros-noetic-topic-tools.patch +++ b/patch/ros-noetic-topic-tools.patch @@ -1,13 +1,21 @@ -diff --git a/src/mux.cpp b/src/mux.cpp -index c7ff5f2816..bd27fdfe8a 100644 ---- a/src/mux.cpp -+++ b/src/mux.cpp -@@ -157,7 +157,7 @@ void in_cb(const boost::shared_ptr& msg, +diff --git a/tools/topic_tools/src/mux.cpp b/tools/topic_tools/src/mux.cpp +index c7ff5f2816..dd7363019c 100644 +--- a/tools/topic_tools/src/mux.cpp ++++ b/tools/topic_tools/src/mux.cpp +@@ -32,6 +32,7 @@ + #include + #include + #include ++#include + #include "ros/console.h" + #include "std_msgs/String.h" + #include "topic_tools/MuxSelect.h" +@@ -157,7 +158,7 @@ void in_cb(const boost::shared_ptr& msg, // we need sleep for publisher initialization // otherwise the first topic will drop. if (g_wait_pub_init) { - usleep(g_wait_second * 1000000); -+ std::this_thread::sleep_for(std::chrono::microseconds(g_wait_second * 1000000)); ++ std::this_thread::sleep_for(std::chrono::microseconds(static_cast(g_wait_second * 1000000))); } g_advertised = true;