Skip to content

Commit 4d8bc07

Browse files
authored
Scaled jtc (backport #1191) (#2105)
1 parent cb7f404 commit 4d8bc07

11 files changed

+686
-5
lines changed

doc/release_notes.rst

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,10 @@ joint_trajectory_controller
7676
don't contain velocity / acceleration information, but the trajectory does. This way, the segment
7777
up to the first waypoint will use the same interpolation as the rest of the trajectory. (`#2043
7878
<https://github.com/ros-controls/ros2_controllers/pull/2043>`_)
79+
* Scaling support was added in `#1191
80+
<https://github.com/ros-controls/ros2_controllers/pull/1191>`__. With this the controller
81+
"stretches the time" with which it progresses in the trajectory. Scaling can either be set
82+
manually or it can be synchronized with the hardware. See :ref:`jtc_speed_scaling` for details.
7983

8084
mecanum_drive_controller
8185
************************
Lines changed: 110 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,110 @@
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.
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
@@ -209,6 +209,7 @@ Further information
209209
:titlesonly:
210210

211211
Trajectory Representation <trajectory.rst>
212+
Speed scaling <speed_scaling.rst>
212213
joint_trajectory_controller Parameters <parameters.rst>
213214
rqt_joint_trajectory_controller <../../rqt_joint_trajectory_controller/doc/userdoc.rst>
214215

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 31 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,9 +23,11 @@
2323

2424
#include "control_msgs/action/follow_joint_trajectory.hpp"
2525
#include "control_msgs/msg/joint_trajectory_controller_state.hpp"
26+
#include "control_msgs/msg/speed_scaling_factor.hpp"
2627
#include "control_msgs/srv/query_trajectory_state.hpp"
2728
#include "control_toolbox/pid.hpp"
2829
#include "controller_interface/controller_interface.hpp"
30+
#include "hardware_interface/loaned_command_interface.hpp"
2931
#include "hardware_interface/types/hardware_interface_type_values.hpp"
3032
#include "joint_trajectory_controller/interpolation_methods.hpp"
3133
#include "joint_trajectory_controller/tolerances.hpp"
@@ -123,6 +125,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
123125

124126
InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
125127
InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
128+
std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
129+
scaling_state_interface_;
130+
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
131+
scaling_command_interface_;
126132

127133
bool has_position_state_interface_ = false;
128134
bool has_velocity_state_interface_ = false;
@@ -144,6 +150,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
144150
// reserved storage for result of the command when closed loop pid adapter is used
145151
std::vector<double> tmp_command_;
146152

153+
// Things around speed scaling
154+
std::atomic<double> scaling_factor_{1.0};
155+
std::atomic<double> scaling_factor_cmd_{1.0};
156+
147157
// Timeout to consider commands old
148158
double cmd_timeout_;
149159
// True if holding position or repeating last trajectory point in case of success
@@ -269,6 +279,27 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
269279
void resize_joint_trajectory_point_command(
270280
trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size, double value = 0.0);
271281

282+
/**
283+
* @brief Set scaling factor used for speed scaling trajectory execution
284+
*
285+
* If the hardware supports and has configured setting speed scaling, that will be sent to the
286+
* hardware's command interface.
287+
*
288+
* If the hardware doesn't support a command interface for speed scaling, but a state interface
289+
* for reading speed scaling, calling this function will have no effect, as the factor will be
290+
* overwritten by the state interface.
291+
*
292+
* @param scaling_factor has to be >= 0
293+
*
294+
* @return True if the value was valid and set, false if the value is < 0
295+
* interval
296+
*
297+
*/
298+
bool set_scaling_factor(double scaling_factor);
299+
300+
using SpeedScalingMsg = control_msgs::msg::SpeedScalingFactor;
301+
rclcpp::Subscription<SpeedScalingMsg>::SharedPtr scaling_factor_sub_;
302+
272303
/**
273304
* @brief Assigns the values from a trajectory point interface to a joint interface.
274305
*

0 commit comments

Comments
 (0)