From 02a2846aa2ed44b58c28b1e5386ec0f99686e0e3 Mon Sep 17 00:00:00 2001 From: Tobias Fischer Date: Wed, 14 Feb 2024 10:40:38 +1000 Subject: [PATCH] Create ros-humble-gazebo-ros2-control.patch --- patch/ros-humble-gazebo-ros2-control.patch | 22 ++++++++++++++++++++++ 1 file changed, 22 insertions(+) create mode 100644 patch/ros-humble-gazebo-ros2-control.patch diff --git a/patch/ros-humble-gazebo-ros2-control.patch b/patch/ros-humble-gazebo-ros2-control.patch new file mode 100644 index 00000000..9b406e5f --- /dev/null +++ b/patch/ros-humble-gazebo-ros2-control.patch @@ -0,0 +1,22 @@ +diff --git a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +index 1ed72fc..6015669 100644 +--- a/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp ++++ b/gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp +@@ -36,6 +36,8 @@ + #include + #include + #include ++#include ++#include + + #include "gazebo_ros/node.hpp" + +@@ -506,7 +508,7 @@ std::string GazeboRosControlPrivate::getURDF(std::string param_name) const + model_nh_->get_logger(), "gazebo_ros2_control plugin is waiting for model" + " URDF in parameter [%s] on the ROS param server.", param_name.c_str()); + } +- usleep(100000); ++ std::this_thread::sleep_for(std::chrono::microseconds(100000)); + } + RCLCPP_INFO( + model_nh_->get_logger(), "Received urdf from param server, parsing...");