|
| 1 | +.. _jtc_speed_scaling: |
| 2 | + |
| 3 | +Speed scaling |
| 4 | +============= |
| 5 | + |
| 6 | +The ``joint_trajectory_controller`` (JTC) supports dynamically scaling its trajectory execution speed. |
| 7 | +That means, when specifying a scaling factor :math:`{f}` of less than 1, execution will proceed only |
| 8 | +:math:`{f \cdot \Delta_t}` per control step where :math:`{\Delta_t}` is the controller's cycle time. |
| 9 | + |
| 10 | +Methods of speed scaling |
| 11 | +------------------------ |
| 12 | + |
| 13 | +Generally, the speed scaling feature has two separate scaling approaches in mind: On-Robot scaling |
| 14 | +and On-Controller scaling. They are both conceptually different and to correctly configure speed |
| 15 | +scaling it is important to understand the differences. |
| 16 | + |
| 17 | +On-Robot speed scaling |
| 18 | +~~~~~~~~~~~~~~~~~~~~~~ |
| 19 | + |
| 20 | +This scaling method is intended for robots that provide a scaling feature directly on the robot's |
| 21 | +teach pendant and / or through a safety feature. One example of such robots are the `Universal |
| 22 | +Robots manipulators <https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver>`_. |
| 23 | + |
| 24 | +The hardware interface needs to report the speed scaling through a state interface so it can be |
| 25 | +read by the controller. Optionally, a command interface for setting the speed scaling value on the |
| 26 | +hardware can be provided (if applicable) in order to set speed scaling through a ROS topic. |
| 27 | + |
| 28 | +For the scope of this documentation a user-defined scaling and a safety-limited scaling will be |
| 29 | +treated the same resulting in a "hardware scaling factor". |
| 30 | + |
| 31 | +In this setup, the hardware will treat the command sent from the ROS controller (e.g. Reach joint |
| 32 | +configuration :math:`{\theta}` within :math:`{\Delta_t}` seconds.). This effectively means that the |
| 33 | +robot will only make half of the way towards the target configuration when a scaling factor of 0.5 |
| 34 | +is given (neglecting acceleration and deceleration influences during this time period). |
| 35 | + |
| 36 | +The following plot shows trajectory execution (for one joint) with a hardware-scaled execution and |
| 37 | +a controller that is **not** aware of speed scaling: |
| 38 | + |
| 39 | +.. image:: traj_without_speed_scaling.png |
| 40 | + :alt: Trajectory with a hardware-scaled-down execution with a non-scaled controller |
| 41 | + |
| 42 | +The graph shows a trajectory with one joint being moved to a target point and back to its starting |
| 43 | +point. As the joint's speed is limited to a very low setting on the teach pendant, speed scaling |
| 44 | +(black line) activates and limits the joint speed (green line). As a result, the target trajectory |
| 45 | +(light blue) doesn't get executed by the robot, but instead the pink trajectory is executed. The |
| 46 | +vertical distance between the light blue line and the pink line is the path error in each control |
| 47 | +cycle. We can see that the path deviation gets above 300 degrees at some point and the target point |
| 48 | +at -6 radians never gets reached. |
| 49 | + |
| 50 | +With the scaled version of the trajectory controller the example motion shown in the previous diagram becomes: |
| 51 | + |
| 52 | +.. image:: traj_with_speed_scaling.png |
| 53 | + :alt: Trajectory with a hardware-scaled-down execution with a scaled controller |
| 54 | + |
| 55 | +The deviation between trajectory interpolation on the ROS side and actual robot execution stays |
| 56 | +minimal and the robot reaches the intermediate setpoint instead of returning "too early" as in the |
| 57 | +example above. |
| 58 | + |
| 59 | +Scaling is done in such a way, that the time in the trajectory is virtually scaled. For example, if |
| 60 | +a controller runs with a cycle time of 100 Hz, each control cycle is 10 ms long. A speed scaling of |
| 61 | +0.5 means that in each time step the trajectory is moved forward by 5 ms instead. |
| 62 | +So, the beginning of the 3rd timestep is 15 ms instead of 30 ms in the trajectory. |
| 63 | + |
| 64 | +Command sampling is performed as in the unscaled case, with the timestep's start plus the **full** |
| 65 | +cycle time of 10 ms. The robot will scale down the motion command by 50% resulting in only half of |
| 66 | +the distance being executed, which is why the next control cycle will be started at the current |
| 67 | +start plus half of the step time. |
| 68 | + |
| 69 | + |
| 70 | +On-Controller speed scaling |
| 71 | +~~~~~~~~~~~~~~~~~~~~~~~~~~~ |
| 72 | + |
| 73 | +Conceptually, with this scaling the robot hardware isn't aware of any scaling happening. The JTC |
| 74 | +generates commands to be sent to the robot that are already scaled down accordingly, so they can be |
| 75 | +directly executed by the robot. |
| 76 | + |
| 77 | +Since the hardware isn't aware of speed scaling, the speed-scaling related command and state |
| 78 | +interfaces should not be specified and the scaling factor will be set through the |
| 79 | +``~/speed_scaling_input`` topic directly: |
| 80 | + |
| 81 | +.. code:: console |
| 82 | +
|
| 83 | + $ ros2 topic pub --qos-durability transient_local --once \ |
| 84 | + /joint_trajectory_controller/speed_scaling_input control_msgs/msg/SpeedScalingFactor "{factor: 0.5}" |
| 85 | +
|
| 86 | +
|
| 87 | +.. note:: |
| 88 | + The ``~/speed_scaling_input`` topic uses the QoS durability profile ``transient_local``. This |
| 89 | + means you can restart the controller while still having a publisher on that topic active. |
| 90 | + |
| 91 | +.. note:: |
| 92 | + The current implementation only works for position-based interfaces. |
| 93 | + |
| 94 | + |
| 95 | +Effect on tolerances |
| 96 | +-------------------- |
| 97 | + |
| 98 | +When speed scaling is used while executing a trajectory, the tolerances configured for execution |
| 99 | +will be scaled, as well. |
| 100 | + |
| 101 | +Since commands are generated from the scaled trajectory time, **path errors** will also be compared |
| 102 | +to the scaled trajectory. |
| 103 | + |
| 104 | +The **goal time tolerance** also uses the virtual trajectory time. This means that a trajectory |
| 105 | +being executed with a constant scaling factor of 0.5 will take twice as long for execution than the |
| 106 | +``time_from_start`` value of the last trajectory point specifies. As long as the robot doesn't take |
| 107 | +longer than that the goal time tolerance is considered to be met. |
| 108 | + |
| 109 | +If an application relies on the actual execution time as set in the ``time_from_start`` fields, an |
| 110 | +external monitoring has to be wrapped around the trajectory execution action. |
0 commit comments