Skip to content

Commit ef32527

Browse files
authored
Merge branch 'moveit:main' into main
2 parents 8769244 + 2ecfb08 commit ef32527

File tree

1 file changed

+22
-2
lines changed

1 file changed

+22
-2
lines changed

doc/examples/controller_configuration/controller_configuration_tutorial.rst

Lines changed: 22 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,24 @@ For each controller it is optional to set the *allowed_execution_duration_scalin
5353
allowed_execution_duration_scaling: 1.2
5454
allowed_goal_duration_margin: 0.5
5555

56+
Optional Parameters for ros_control Interface
57+
------------------
58+
59+
When using the MoveIt ROS Control interface, you can configure several parameters to optimize its behavior:
60+
61+
**controller_service_call_timeout** (double, default: 3.0 seconds)
62+
This parameter controls how long MoveIt will wait for responses from controller manager services like list_controllers and switch_controller. On resource-constrained systems or congested networks, controller discovery and switching operations can take longer than the default timeout. Increasing this parameter in your configuration can prevent these timeout issues.
63+
64+
**ros_control_namespace** (string, default: "/")
65+
Namespace of the ros_control node.
66+
67+
.. code-block:: yaml
68+
69+
# In your moveit_controllers.yaml configuration
70+
ros_control_namespace: /my_robot
71+
controller_service_call_timeout: 5.0 # Increase timeout to 5 seconds
72+
73+
5674
Debugging Information
5775
---------------------
5876

@@ -106,13 +124,15 @@ If you do not have a physical robot, :code:`ros2_control` makes it very easy to
106124
Controller Switching and Namespaces
107125
-----------------------------------
108126

109-
(TODO: update for ROS2)
110-
111127
All controller names get prefixed by the namespace of their ros_control node. For this reason controller names should not contain slashes, and can't be named ``/``. For a particular node MoveIt can decide which controllers to have started or stopped. Since only controller names with registered allocator plugins are handled over MoveIt, MoveIt takes care of stopping controllers based on their claimed resources if a to-be-started controller needs any of those resources.
112128

129+
When working with controller switching through the ROS Control interface managers, you can configure the timeout for controller manager service calls using the :code:`controller_service_call_timeout` parameter (default: 3.0 seconds). This is particularly useful in complex setups where controller switching might take longer than the default timeout.
130+
113131
Controllers for Multiple Nodes
114132
------------------------------
115133

116134
There is a variation on the Ros2ControlManager, the Ros2ControlMultiManager. Ros2ControlMultiManager can be used for more than one ros_control nodes. It works by creating several Ros2ControlManagers, one for each node. It instantiates them with their respective namespace and takes care of proper delegation. To use it must be added to the launch file. ::
117135

118136
<param name="moveit_controller_manager" value="moveit_ros_control_interface::Ros2ControlMultiManager" />
137+
138+
The :code:`controller_service_call_timeout` parameter can also be set with the Ros2ControlMultiManager and will be used by all discovered controller managers.

0 commit comments

Comments
 (0)