From 816bea09b4dcd60fd20ca872d15cf0c59610b76d Mon Sep 17 00:00:00 2001 From: Chris Iverach-Brereton <59611394+civerachb-cpr@users.noreply.github.com> Date: Thu, 19 Sep 2024 10:35:37 -0400 Subject: [PATCH] Add 30s timeout for controller spawners (#233) * Add 30s timeout for controller spawners It looks like the latest ros_controllers release has a default timeout that's too short to allow Gazebo to properly start up, resulting in the diff drive controller & joint state broadcaster to time-out rather than starting up. Adding an explicit timeout appears to work around this issue. * copy & paste error --- .../launch/include/control.py | 16 ++++++++++++++-- 1 file changed, 14 insertions(+), 2 deletions(-) diff --git a/irobot_create_common/irobot_create_control/launch/include/control.py b/irobot_create_common/irobot_create_control/launch/include/control.py index 26aa2497..2fea124e 100644 --- a/irobot_create_common/irobot_create_control/launch/include/control.py +++ b/irobot_create_common/irobot_create_control/launch/include/control.py @@ -30,14 +30,26 @@ def generate_launch_description(): executable='spawner', namespace=namespace, # Namespace is not pushed when used in EventHandler parameters=[control_params_file], - arguments=['diffdrive_controller', '-c', 'controller_manager'], + arguments=[ + 'diffdrive_controller', + '-c', + 'controller_manager', + '--controller-manager-timeout', + '30' + ], output='screen', ) joint_state_broadcaster_spawner = Node( package='controller_manager', executable='spawner', - arguments=['joint_state_broadcaster', '-c', 'controller_manager'], + arguments=[ + 'joint_state_broadcaster', + '-c', + 'controller_manager', + '--controller-manager-timeout', + '30' + ], output='screen', )