Skip to content

Commit 0584835

Browse files
Felix Exnergavanderhoorn
andauthored
Added explanation of scaled trajectory controller (UniversalRobots#250)
* Added explanation of scaled trajectory controller * Apply suggestions from code review Thanks @gavanderhoorn for this in-depth review! Co-authored-by: G.A. vd. Hoorn <[email protected]> * Added another suggestion I missed Co-authored-by: G.A. vd. Hoorn <[email protected]> * Clarified where the speed_scaling value comes from. * Format ros_control correctly * Rewrote bullet point about non-moving robot * Replace time frame with control cycle Co-authored-by: G.A. vd. Hoorn <[email protected]>
1 parent 3d4763a commit 0584835

File tree

3 files changed

+63
-5
lines changed

3 files changed

+63
-5
lines changed

ur_controllers/README.md

Lines changed: 63 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,18 +1,76 @@
11
# ur_controllers
22

3-
This package contains controllers and hardware interface for ROS control that are special to the UR
3+
This package contains controllers and hardware interface for `ros_control` that are special to the UR
44
robot family. Currently this contains
55

66
* A **speed_scaling_interface** to read the value of the current speed scaling into controllers.
77
* A **scaled_joint_command_interface** that provides access to joint values and commands in
88
combination with the speed scaling value.
9-
* A **speed_scaling_state_controller** that publishes the current value of the speed scaling
10-
to a topic interface.
9+
* A **speed_scaling_state_controller** that publishes the current execution speed as reported by
10+
the robot to a topic interface. Values are floating points between 0 and 1.
1111
* A **scaled_joint_trajectory_controller** that is similar to the *joint_trajectory_controller*,
1212
but it uses the speed scaling reported by the robot to reduce progress in the trajectory.
1313

1414
## About this package
15-
This package contains controllers not being available in the default ROS-Control set. They are
15+
This package contains controllers not being available in the default `ros_control` set. They are
1616
created to support more features offered by the UR robot family. Any of these controllers are
1717
example implementations for certain features and are intended to be generalized and merged
18-
into the default ROS-Control controller set at some future point.
18+
into the default `ros_control` controller set at some future point.
19+
20+
## Controller description
21+
This packages offers a couple of specific controllers that will be explained in the following
22+
sections.
23+
### ur_controllers/SpeedScalingStateController
24+
This controller publishes the current actual execution speed as reported by the robot. Values are
25+
floating points between 0 and 1.
26+
27+
In the [`ur_robot_driver`](../ur_robot_driver) this is calculated by multiplying the two [RTDE](https://www.universal-robots.com/articles/ur/real-time-data-exchange-rtde-guide/) data
28+
fields `speed_scaling` (which should be equal to the value shown by the speed slider position on the
29+
teach pendant) and `target_speed_fraction` (Which is the fraction to which execution gets slowed
30+
down by the controller).
31+
### position_controllers/ScaledJointTrajectoryController and velocity_controllers/ScaledJointTrajectoryController
32+
These controllers work similar to the well-known
33+
[`joint_trajectory_controller`](http://wiki.ros.org/joint_trajectory_controller).
34+
35+
However, they are extended to handle the robot's execution speed specifically. Because the default
36+
`joint_trajectory_controller` would interpolate the trajectory with the configured time constraints (ie: always assume maximum velocity and acceleration supported by the robot),
37+
this could lead to significant path deviation due to multiple reasons:
38+
- The speed slider on the robot might not be at 100%, so motion commands sent from ROS would
39+
effectively get scaled down resulting in a slower execution.
40+
- The robot could scale down motions based on configured safety limits resulting in a slower motion
41+
than expected and therefore not reaching the desired target in a control cycle.
42+
- Motions might not be executed at all, e.g. because the robot is E-stopped or in a protective stop
43+
- Motion commands sent to the robot might not be interpreted, e.g. because there is no
44+
[`external_control`](https://github.com/UniversalRobots/Universal_Robots_ROS_Driver#prepare-the-robot)
45+
program node running on the robot controller.
46+
- The program interpreting motion commands could be paused.
47+
48+
The following plot illustrates the problem:
49+
![Trajectory execution with default trajectory controller](doc/traj_without_speed_scaling.png
50+
"Trajectory execution with default trajectory controller")
51+
52+
The graph shows a trajectory with one joint being moved to a target point and back to its starting
53+
point. As the joint's speed is limited to a very low setting on the teach pendant, speed scaling
54+
(black line) activates and limits the joint speed (green line). As a result, the target
55+
trajectory (light blue) doesn't get executed by the robot, but instead the pink trajectory is executed.
56+
The vertical distance between the light blue line and the pink line is the path error in each
57+
control cycle. We can see that the path deviation gets above 300 degrees at some point and the
58+
target point at -6 radians never gets reached.
59+
60+
All of the cases mentioned above are addressed by the scaled trajectory versions. Trajectory execution
61+
can be transparently scaled down using the speed slider on the teach pendant without leading to
62+
additional path deviations. Pausing the program or hitting the E-stop effectively leads to
63+
`speed_scaling` being 0 meaning the trajectory will not be continued until the program is continued.
64+
This way, trajectory executions can be explicitly paused and continued.
65+
66+
With the scaled version of the trajectory controller the example motion shown in the previous diagram becomes:
67+
![Trajectory execution with scaled_joint_trajectory_controller](doc/traj_with_speed_scaling.png
68+
"Trajectory execution with scaled_joint_trajectory_controller")
69+
70+
The deviation between trajectory interpolation on the ROS side and actual robot execution stays minimal and the
71+
robot reaches the intermediate setpoint instead of returning "too early" as in the example above.
72+
73+
Under the hood this is implemented by proceeding the trajectory not by a full time step but only by
74+
the fraction determined by the current speed scaling. If speed scaling is currently at 50% then
75+
interpolation of the current control cycle will start half a time step after the beginning of the
76+
previous control cycle.
102 KB
Loading
105 KB
Loading

0 commit comments

Comments
 (0)