|
1 | 1 | Controllers |
2 | 2 | =========== |
3 | 3 |
|
4 | | -.. todo:: |
5 | | - Write something... |
| 4 | +This help page describes the different controllers available for the ``ur_robot_driver``. This |
| 5 | +should help users finding the right controller for their specific use case. |
| 6 | + |
| 7 | +Where are controllers defined? |
| 8 | +------------------------------ |
| 9 | + |
| 10 | +Controllers are defined in the ``config/ur_controllers.yaml`` file. |
| 11 | + |
| 12 | +How do controllers get loaded and started? |
| 13 | +------------------------------------------ |
| 14 | + |
| 15 | +As this driver uses `ros2_control <https://control.ros.org>`_ all controllers are managed by the |
| 16 | +controller_manager. During startup, a default set of running controllers is loaded and started, |
| 17 | +another set is loaded in stopped mode. Stopped controllers won't be usable right away, but they |
| 18 | +need to be started individually. |
| 19 | + |
| 20 | +Controllers that are actually writing to some command interfaces (e.g. joint positions) will claim |
| 21 | +those interfaces. Only one controller claiming a certain interface can be active at one point. |
| 22 | + |
| 23 | +Controllers can be switched either through the controller_manager's service calls, through the |
| 24 | +`rqt_controller_manager <https://control.ros.org/rolling/doc/ros2_control/controller_manager/doc/userdoc.html#rqt-controller-manager>`_ gui or through the ``ros2 control`` verb from the package ``ros-${ROS_DISTRO}-ros2controlcli`` package. |
| 25 | + |
| 26 | +For example, to switch from the default ``scaled_joint_trajectory_controller`` to the |
| 27 | +``forward_position_controller`` you can call |
| 28 | + |
| 29 | +.. code-block:: console |
| 30 | +
|
| 31 | + $ ros2 control switch_controllers --deactivate scaled_joint_trajectory_controller \ |
| 32 | + --activate forward_position_controller |
| 33 | + [INFO 2024-09-23 20:32:04.373] [_ros2cli_1207798]: waiting for service /controller_manager/switch_controller to become available... |
| 34 | + Successfully switched controllers |
| 35 | +
|
| 36 | +Read-only broadcasters |
| 37 | +---------------------- |
| 38 | + |
| 39 | +These broadcasters are read-only. They read states from the robot and publish them on a ROS topic. |
| 40 | +As they are read-only, they don't claim any resources and can be combined freely. By default, they |
| 41 | +are all started and running. Those controllers do not require the robot to have the |
| 42 | +external_control script running. |
| 43 | + |
| 44 | +joint_state_broadcaster |
| 45 | +^^^^^^^^^^^^^^^^^^^^^^^ |
| 46 | + |
| 47 | +Type: `joint_state_broadcaster/JointStateBroadcaster <https://control.ros.org/rolling/doc/ros2_controllers/joint_state_broadcaster/doc/userdoc.html>`_ |
| 48 | + |
| 49 | +Publishes all joints' positions, velocities, and motor currents as ``sensor_msgs/JointState`` on the ``joint_states`` topic. |
| 50 | + |
| 51 | +.. note:: |
| 52 | + |
| 53 | + The effort field contains the currents reported by the joints and not the actual efforts in a |
| 54 | + physical sense. |
| 55 | + |
| 56 | +speed_scaling_state_broadcaster |
| 57 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 58 | + |
| 59 | +Type: :ref:`ur_controllers/SpeedScalingStateBroadcaster <speed_scaling_state_broadcaster>` |
| 60 | + |
| 61 | +This broadcaster publishes the current actual execution speed as reported by the robot. Values are |
| 62 | +floating points between 0 and 1. |
| 63 | + |
| 64 | +force_torque_sensor_broadcaster |
| 65 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 66 | + |
| 67 | +Type: `force_torque_sensor_broadcaster/ForceTorqueSensorBroadcaster <https://control.ros.org/rolling/doc/ros2_controllers/force_torque_sensor_broadcaster/doc/userdoc.html>`_ |
| 68 | + |
| 69 | +Publishes the robot's wrench as reported from the controller. |
| 70 | + |
| 71 | +Commanding controllers |
| 72 | +---------------------- |
| 73 | + |
| 74 | +The commanding controllers control the robot's motions. Those controllers can't be combined |
| 75 | +arbitrarily, as they will claim hardware resources. Only one controller can claim one hardware |
| 76 | +resource at a time. |
| 77 | + |
| 78 | +scaled_joint_trajectory_controller (Default motion controller) |
| 79 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 80 | + |
| 81 | +Type: :ref:`ur_controllers/ScaledJointTrajectoryController <scaled_jtc>` |
| 82 | + |
| 83 | +Scaled version of the |
| 84 | +`joint_trajectory_controller |
| 85 | +<https://control.ros.org/master/doc/ros2_controllers/joint_trajectory_controller/doc/userdoc.html>`_. |
| 86 | +It uses the robot's speed scaling information and can also be paused when pausing the *External |
| 87 | +Control* program. See it's linked documentation for details. |
| 88 | + |
| 89 | +.. note:: |
| 90 | + |
| 91 | + It is planned to replace this controller with ros2_control's joint_trajectory_controller once |
| 92 | + that has received the capability of being scaled, as well. |
| 93 | + |
| 94 | +io_and_status_controller |
| 95 | +^^^^^^^^^^^^^^^^^^^^^^^^ |
| 96 | + |
| 97 | +Type: :ref:`ur_controllers/GPIOController <io_and_status_controller>` |
| 98 | + |
| 99 | +Allows setting I/O ports, controlling some UR-specific functionality and publishes status information about the robot. |
| 100 | + |
| 101 | +forward_velocity_controller |
| 102 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 103 | + |
| 104 | +Type: `velocity_controllers/JointGroupVelocityController <https://control.ros.org/rolling/doc/ros2_controllers/position_controllers/doc/userdoc.html#position-controllers-jointgrouppositioncontroller>`_ |
| 105 | + |
| 106 | +Allows setting target joint positions directly. The robot tries to reach the target position as |
| 107 | +fast as possible. The user is therefore responsible for sending commands that are achievable. This |
| 108 | +controller is particularly useful when doing servoing such as ``moveit_servo``. |
| 109 | + |
| 110 | +forward_position_controller |
| 111 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 112 | + |
| 113 | +Type: `position_controllers/JointGroupPositionController <https://control.ros.org/rolling/doc/ros2_controllers/velocity_controllers/doc/userdoc.html#velocity-controllers-jointgroupvelocitycontroller>`_ |
| 114 | + |
| 115 | +Allows setting target joint velocities directly. The user is responsible for sending commands that |
| 116 | +are achievable. This controller is particularly useful when doing servoing such as |
| 117 | +``moveit_servo``. |
0 commit comments