Skip to content

Commit fa88059

Browse files
author
Felix Exner
committed
WIP: Adding documentation about speed scaling
1 parent b76501a commit fa88059

File tree

4 files changed

+76
-0
lines changed

4 files changed

+76
-0
lines changed
Lines changed: 75 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,75 @@
1+
Speed scaling
2+
=============
3+
4+
The ``joint_trajectory_controller`` (JTC) supports dynamically scaling its trajectory execution speed.
5+
That means, when specifying a scaling factor :math:`{f}` of less than 1, execution will proceed only
6+
:math:`{f \cdot \Delta_t}` per control step where :math:`{\Delta_t}` is the controller's cycle time.
7+
8+
Methods of speed scaling
9+
------------------------
10+
11+
Generally, the speed scaling feature has two separate scaling approaches in mind: On-Robot scaling
12+
and On-Controller scaling. They are both conceptually different and to correctly configure speed
13+
scaling it is important to understand the differences.
14+
15+
On-Robot speed scaling
16+
~~~~~~~~~~~~~~~~~~~~~~
17+
18+
This scaling method is intended for robots that provide a scaling feature directly on the robot's
19+
teach pendant and / or through a safety feature. One example of such robots are the `Universal
20+
Robots manipulators <https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver>`_.
21+
22+
For the scope of this documentation a user-defined scaling and a safety-limited scaling will be
23+
treated the same resulting in a "hardware scaling factor".
24+
25+
In this setup, the hardware will treat the command sent from the ROS controller (e.g. Reach joint
26+
configuration :math:`{\theta}` within :math:`{\Delta_t}` seconds.). This effectively means that the
27+
robot will only make half of the way towards the target configuration when a scaling factor of 0.5
28+
is given (neglectling acceleration and deceleration influcences during this time period).
29+
30+
The following plot shows trajectory execution (for one joint) with a hardware-scaled execution and
31+
a controller that is **not** aware of speed scaling:
32+
33+
.. image:: traj_without_speed_scaling.png
34+
:alt: Trajectory with a hardware-scaled-down execution with a non-scaled controller
35+
36+
The graph shows a trajectory with one joint being moved to a target point and back to its starting
37+
point. As the joint's speed is limited to a very low setting on the teach pendant, speed scaling
38+
(black line) activates and limits the joint speed (green line). As a result, the target trajectory
39+
(light blue) doesn't get executed by the robot, but instead the pink trajectory is executed. The
40+
vertical distance between the light blue line and the pink line is the path error in each control
41+
cycle. We can see that the path deviation gets above 300 degrees at some point and the target point
42+
at -6 radians never gets reached.
43+
44+
With the scaled version of the trajectory controller the example motion shown in the previous diagram becomes:
45+
46+
.. image:: traj_with_speed_scaling.png
47+
:alt: Trajectory with a hardware-scaled-down execution with a scaled controller
48+
49+
The deviation between trajectory interpolation on the ROS side and actual robot execution stays
50+
minimal and the robot reaches the intermediate setpoint instead of returning "too early" as in the
51+
example above.
52+
53+
.. todo:: Describe method behind this scaling approach.
54+
55+
56+
On-Controller speed scaling
57+
~~~~~~~~~~~~~~~~~~~~~~~~~~~
58+
59+
Conceptionally, with this scaling the robot hardware isn't aware of any scaling happening. The JTC
60+
generates commands to be sent to the robot that are already scaled down accordingly, so they can be
61+
directly executed by the robot.
62+
63+
Since the hardware isn't aware of speed scaling, the speed-scaling related command and state
64+
interfaces should not be specified and the scaling factor will be set by the ``setSpeedScaling``
65+
service directly.
66+
67+
.. note::
68+
The current implementation only works for position-based interfaces.
69+
70+
71+
Goal time tolerances
72+
--------------------
73+
74+
.. todo::
75+
What happens to goal time tolerances if we scale down a trajectory?
102 KB
Loading
105 KB
Loading

joint_trajectory_controller/doc/userdoc.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -192,6 +192,7 @@ Further information
192192
:titlesonly:
193193

194194
Trajectory Representation <trajectory.rst>
195+
Speed scaling <speed_scaling.rst>
195196
joint_trajectory_controller Parameters <parameters.rst>
196197
rqt_joint_trajectory_controller <../../rqt_joint_trajectory_controller/doc/userdoc.rst>
197198

0 commit comments

Comments
 (0)