|
| 1 | +ur_controllers |
| 2 | +============== |
| 3 | + |
| 4 | +This package contains controllers and hardware interface for ``ros2_controllers`` that are special to the UR |
| 5 | +robot family. Currently this contains: |
| 6 | + |
| 7 | + |
| 8 | +* A **speed_scaling_state_broadcaster** that publishes the current execution speed as reported by |
| 9 | + the robot to a topic interface. Values are floating points between 0 and 1. |
| 10 | +* A **scaled_joint_trajectory_controller** that is similar to the *joint_trajectory_controller*\ , |
| 11 | + but it uses the speed scaling reported to align progress of the trajectory between the robot and controller. |
| 12 | +* A **io_and_status_controller** that allows setting I/O ports, controlling some UR-specific |
| 13 | + functionality and publishes status information about the robot. |
| 14 | + |
| 15 | +About this package |
| 16 | +------------------ |
| 17 | + |
| 18 | +This package contains controllers not being available in the default ``ros2_controllers`` set. They are |
| 19 | +created to support more features offered by the UR robot family. Some of these controllers are |
| 20 | +example implementations for certain features and are intended to be generalized and merged |
| 21 | +into the default ``ros2_controllers`` controller set at some future point. |
| 22 | + |
| 23 | +Controller description |
| 24 | +---------------------- |
| 25 | + |
| 26 | +This packages offers a couple of specific controllers that will be explained in the following |
| 27 | +sections. |
| 28 | + |
| 29 | +.. _speed_scaling_state_broadcaster: |
| 30 | + |
| 31 | +ur_controllers/SpeedScalingStateBroadcaster |
| 32 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 33 | + |
| 34 | +This controller publishes the current actual execution speed as reported by the robot. Values are |
| 35 | +floating points between 0 and 1. |
| 36 | + |
| 37 | +In the `ur_robot_driver |
| 38 | +<https://index.ros.org/p/ur_robot_driver/github-UniversalRobots-Universal_Robots_ROS2_Driver/>`_ |
| 39 | +this is calculated by multiplying the two `RTDE |
| 40 | +<https://www.universal-robots.com/articles/ur/real-time-data-exchange-rtde-guide/>`_ data |
| 41 | +fields ``speed_scaling`` (which should be equal to the value shown by the speed slider position on the |
| 42 | +teach pendant) and ``target_speed_fraction`` (Which is the fraction to which execution gets slowed |
| 43 | +down by the controller). |
| 44 | + |
| 45 | +.. _scaled_jtc: |
| 46 | + |
| 47 | +ur_controlers/ScaledJointTrajectoryController |
| 48 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 49 | + |
| 50 | +These controllers work similar to the well-known |
| 51 | +`joint_trajectory_controller <https://control.ros.org/master/doc/ros2_controllers/joint_trajectory_controller/doc/userdoc.html>`_. |
| 52 | + |
| 53 | +However, they are extended to handle the robot's execution speed specifically. Because the default |
| 54 | +``joint_trajectory_controller`` would interpolate the trajectory with the configured time constraints (ie: always assume maximum velocity and acceleration supported by the robot), |
| 55 | +this could lead to significant path deviation due to multiple reasons: |
| 56 | + |
| 57 | + |
| 58 | +* The speed slider on the robot might not be at 100%, so motion commands sent from ROS would |
| 59 | + effectively get scaled down resulting in a slower execution. |
| 60 | +* The robot could scale down motions based on configured safety limits resulting in a slower motion |
| 61 | + than expected and therefore not reaching the desired target in a control cycle. |
| 62 | +* Motions might not be executed at all, e.g. because the robot is E-stopped or in a protective stop |
| 63 | +* Motion commands sent to the robot might not be interpreted, e.g. because there is no |
| 64 | + `external_control <https://github.com/UniversalRobots/Universal_Robots_ROS_Driver#prepare-the-robot>`_ |
| 65 | + program node running on the robot controller. |
| 66 | +* The program interpreting motion commands could be paused. |
| 67 | + |
| 68 | +The following plot illustrates the problem: |
| 69 | + |
| 70 | +.. image:: traj_without_speed_scaling.png |
| 71 | + :target: traj_without_speed_scaling.png |
| 72 | + :alt: Trajectory execution with default trajectory controller |
| 73 | + |
| 74 | + |
| 75 | +The graph shows a trajectory with one joint being moved to a target point and back to its starting |
| 76 | +point. As the joint's speed is limited to a very low setting on the teach pendant, speed scaling |
| 77 | +(black line) activates and limits the joint speed (green line). As a result, the target |
| 78 | +trajectory (light blue) doesn't get executed by the robot, but instead the pink trajectory is executed. |
| 79 | +The vertical distance between the light blue line and the pink line is the path error in each |
| 80 | +control cycle. We can see that the path deviation gets above 300 degrees at some point and the |
| 81 | +target point at -6 radians never gets reached. |
| 82 | + |
| 83 | +All of the cases mentioned above are addressed by the scaled trajectory versions. Trajectory execution |
| 84 | +can be transparently scaled down using the speed slider on the teach pendant without leading to |
| 85 | +additional path deviations. Pausing the program or hitting the E-stop effectively leads to |
| 86 | +``speed_scaling`` being 0 meaning the trajectory will not be continued until the program is continued. |
| 87 | +This way, trajectory executions can be explicitly paused and continued. |
| 88 | + |
| 89 | +With the scaled version of the trajectory controller the example motion shown in the previous diagram becomes: |
| 90 | + |
| 91 | +.. image:: traj_with_speed_scaling.png |
| 92 | + :target: traj_with_speed_scaling.png |
| 93 | + :alt: Trajectory execution with scaled_joint_trajectory_controller |
| 94 | + |
| 95 | + |
| 96 | +The deviation between trajectory interpolation on the ROS side and actual robot execution stays minimal and the |
| 97 | +robot reaches the intermediate setpoint instead of returning "too early" as in the example above. |
| 98 | + |
| 99 | +Under the hood this is implemented by proceeding the trajectory not by a full time step but only by |
| 100 | +the fraction determined by the current speed scaling. If speed scaling is currently at 50% then |
| 101 | +interpolation of the current control cycle will start half a time step after the beginning of the |
| 102 | +previous control cycle. |
| 103 | + |
| 104 | +.. _io_and_status_controller: |
| 105 | + |
| 106 | +ur_controllers/GPIOController |
| 107 | +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ |
| 108 | + |
| 109 | +This controller allows setting I/O ports, controlling some UR-specific functionality and publishes |
| 110 | +status information about the robot. |
| 111 | + |
| 112 | +Published topics |
| 113 | +"""""""""""""""" |
| 114 | + |
| 115 | +* ``~/io_states [ur_msgs/msg/IOStates]``: Status of all I/O ports |
| 116 | +* ``~/robot_mode [ur_dashboard_msgs/msg/RobotMode]``: The current robot mode (e.g. ``POWER_OFF``, |
| 117 | + ``IDLE``, ``RUNNING``) |
| 118 | +* ``~/robot_program_running [std_msgs/msg/Bool]``: Publishes whether **the External Control |
| 119 | + program** is running or not. If this is ``false`` no commands can be sent to the robot. |
| 120 | +* ``~/safety_mode [ur_dashboard_msgs/msg/SafetyMode]``: The robot's current safety mode (e.g. |
| 121 | + ``PROTECTIVE_STOP``, ``ROBOT_EMERGENCY_STOP``, ``NORMAL``) |
| 122 | +* ``~/tool_data [ur_msgs/msg/ToolDataMsg]``: Information about the robot's tool configuration |
| 123 | + |
| 124 | +Advertised services |
| 125 | +""""""""""""""""""" |
| 126 | + |
| 127 | +* ``~/hand_back_control [std_srvs/srv/Trigger]``: Calling this service will make the robot program |
| 128 | + exit the *External Control* program node and continue with the rest of the program. |
| 129 | +* ``~/resend_robot_program [std_srvs/srv/Trigger]``: When :ref:`headless_mode` is used, this |
| 130 | + service can be used to restart the *External Control* program on the robot. |
| 131 | +* ``~/set_io [ur_msgs/srv/SetIO]``: Set an output pin on the robot. |
| 132 | +* ``~/set_analog_output [ur_msgs/srv/SetAnalogOutput]``: Set an analog output on the robot. This |
| 133 | + also allows specifying the domain. |
| 134 | +* ``~/set_payload [ur_msgs/srv/SetPayload]``: Change the robot's payload on-the-fly. |
| 135 | +* ``~/set_speed_slider [ur_msgs/srv/SetSpeedSliderFraction]``: Set the value of the speed slider. |
| 136 | +* ``~/zero_ftsensor [std_srvs/srv/Trigger]``: Zeroes the reported wrench of the force torque |
| 137 | + sensor. |
0 commit comments