Skip to content

Commit

Permalink
Add 30s timeout for controller spawners (#233)
Browse files Browse the repository at this point in the history
* 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
  • Loading branch information
civerachb-cpr authored and Alberto Soragna committed Sep 19, 2024
1 parent 480bfa1 commit 816bea0
Showing 1 changed file with 14 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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',
)

Expand Down

0 comments on commit 816bea0

Please sign in to comment.