Skip to content

Commit 4a42b1f

Browse files
fmauchchristophfroehlichmamueluthLennart Nachtigalldestogl
authored
Add speed scaling support to JTC (#1191)
Co-authored-by: Christoph Fröhlich <[email protected]> Co-authored-by: Manuel M <[email protected]> Co-authored-by: Lennart Nachtigall <[email protected]> Co-authored-by: Dr. Denis <[email protected]> Co-authored-by: Sai Kishor Kothakota <[email protected]>
1 parent fc41a09 commit 4a42b1f

11 files changed

+684
-2
lines changed

doc/release_notes.rst

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,10 @@ force_torque_sensor_broadcaster
1111
joint_trajectory_controller
1212
*******************************
1313
* The controller now supports the new anti-windup strategy of the PID class, which allows for more flexible control of the anti-windup behavior. (`#1759 <https://github.com/ros-controls/ros2_controllers/pull/1759>`__).
14+
* Scaling support was added in `#1191
15+
<https://github.com/ros-controls/ros2_controllers/pull/1191>`__. With this the controller
16+
"stretches the time" with which it progresses in the trajectory. Scaling can either be set
17+
manually or it can be synchronized with the hardware. See :ref:`jtc_speed_scaling` for details.
1418

1519
pid_controller
1620
*******************************
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"
@@ -129,6 +131,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
129131

130132
InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
131133
InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
134+
std::optional<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
135+
scaling_state_interface_;
136+
std::optional<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
137+
scaling_command_interface_;
132138

133139
bool has_position_state_interface_ = false;
134140
bool has_velocity_state_interface_ = false;
@@ -150,6 +156,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
150156
// reserved storage for result of the command when closed loop pid adapter is used
151157
std::vector<double> tmp_command_;
152158

159+
// Things around speed scaling
160+
std::atomic<double> scaling_factor_{1.0};
161+
std::atomic<double> scaling_factor_cmd_{1.0};
162+
153163
// Timeout to consider commands old
154164
double cmd_timeout_;
155165
// True if holding position or repeating last trajectory point in case of success
@@ -274,6 +284,27 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
274284
void resize_joint_trajectory_point_command(
275285
trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size, double value = 0.0);
276286

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

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 134 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -113,6 +113,10 @@ JointTrajectoryController::command_interface_configuration() const
113113
conf.names.push_back(joint_name + "/" + interface_type);
114114
}
115115
}
116+
if (!params_.speed_scaling.command_interface.empty())
117+
{
118+
conf.names.push_back(params_.speed_scaling.command_interface);
119+
}
116120
return conf;
117121
}
118122

@@ -129,12 +133,30 @@ JointTrajectoryController::state_interface_configuration() const
129133
conf.names.push_back(joint_name + "/" + interface_type);
130134
}
131135
}
136+
if (!params_.speed_scaling.state_interface.empty())
137+
{
138+
conf.names.push_back(params_.speed_scaling.state_interface);
139+
}
132140
return conf;
133141
}
134142

135143
controller_interface::return_type JointTrajectoryController::update(
136144
const rclcpp::Time & time, const rclcpp::Duration & period)
137145
{
146+
if (scaling_state_interface_.has_value())
147+
{
148+
scaling_factor_ = scaling_state_interface_->get().get_value();
149+
}
150+
151+
if (scaling_command_interface_.has_value())
152+
{
153+
if (!scaling_command_interface_->get().set_value(scaling_factor_cmd_.load()))
154+
{
155+
RCLCPP_ERROR(
156+
get_node()->get_logger(), "Could not set speed scaling factor through command interfaces.");
157+
}
158+
}
159+
138160
auto logger = this->get_node()->get_logger();
139161
// update dynamic parameters
140162
if (param_listener_->is_old(params_))
@@ -197,18 +219,21 @@ controller_interface::return_type JointTrajectoryController::update(
197219
}
198220
else
199221
{
200-
traj_time_ += period;
222+
traj_time_ += period * scaling_factor_.load();
201223
}
202224

203225
// Sample expected state from the trajectory
204226
current_trajectory_->sample(
205227
traj_time_, interpolation_method_, state_desired_, start_segment_itr, end_segment_itr);
228+
state_desired_.time_from_start = traj_time_ - current_trajectory_->time_from_start();
206229

207230
// Sample setpoint for next control cycle
208231
const bool valid_point = current_trajectory_->sample(
209232
traj_time_ + update_period_, interpolation_method_, command_next_, start_segment_itr,
210233
end_segment_itr, false);
211234

235+
state_current_.time_from_start = time - current_trajectory_->time_from_start();
236+
212237
if (valid_point)
213238
{
214239
const rclcpp::Time traj_start = current_trajectory_->time_from_start();
@@ -937,10 +962,47 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
937962
resize_joint_trajectory_point(
938963
last_commanded_state_, dof_, std::numeric_limits<double>::quiet_NaN());
939964

965+
// create services
940966
query_state_srv_ = get_node()->create_service<control_msgs::srv::QueryTrajectoryState>(
941967
std::string(get_node()->get_name()) + "/query_state",
942968
std::bind(&JointTrajectoryController::query_state_service, this, _1, _2));
943969

970+
if (
971+
!has_velocity_command_interface_ && !has_acceleration_command_interface_ &&
972+
!has_effort_command_interface_)
973+
{
974+
auto qos = rclcpp::SystemDefaultsQoS();
975+
qos.transient_local();
976+
scaling_factor_sub_ = get_node()->create_subscription<SpeedScalingMsg>(
977+
"~/speed_scaling_input", qos,
978+
[&](const SpeedScalingMsg & msg) { set_scaling_factor(msg.factor); });
979+
RCLCPP_INFO(
980+
logger, "Setting initial scaling factor to %2f",
981+
params_.speed_scaling.initial_scaling_factor);
982+
scaling_factor_ = params_.speed_scaling.initial_scaling_factor;
983+
}
984+
else
985+
{
986+
RCLCPP_WARN_EXPRESSION(
987+
logger, params_.speed_scaling.initial_scaling_factor != 1.0,
988+
"Speed scaling is currently only supported for position interfaces. If you want to make use "
989+
"of speed scaling, please only use a position interface when configuring this controller.");
990+
scaling_factor_ = 1.0;
991+
}
992+
if (!params_.speed_scaling.state_interface.empty())
993+
{
994+
RCLCPP_INFO(
995+
logger, "Using scaling state from the hardware from interface %s.",
996+
params_.speed_scaling.state_interface.c_str());
997+
}
998+
else
999+
{
1000+
RCLCPP_INFO(
1001+
get_node()->get_logger(),
1002+
"No scaling interface set. This controller will not read speed scaling from the hardware.");
1003+
}
1004+
scaling_factor_cmd_.store(scaling_factor_.load());
1005+
9441006
if (get_update_rate() == 0)
9451007
{
9461008
throw std::runtime_error("Controller's update rate is set to 0. This should not happen!");
@@ -965,6 +1027,42 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
9651027
// parse remaining parameters
9661028
default_tolerances_ = get_segment_tolerances(logger, params_);
9671029

1030+
// Set scaling interfaces
1031+
if (!params_.speed_scaling.state_interface.empty())
1032+
{
1033+
auto it = std::find_if(
1034+
state_interfaces_.begin(), state_interfaces_.end(), [&](auto & interface)
1035+
{ return (interface.get_name() == params_.speed_scaling.state_interface); });
1036+
if (it != state_interfaces_.end())
1037+
{
1038+
scaling_state_interface_ = *it;
1039+
}
1040+
else
1041+
{
1042+
RCLCPP_ERROR(
1043+
logger, "Did not find speed scaling interface '%s' in state interfaces.",
1044+
params_.speed_scaling.state_interface.c_str());
1045+
return CallbackReturn::ERROR;
1046+
}
1047+
}
1048+
if (!params_.speed_scaling.command_interface.empty())
1049+
{
1050+
auto it = std::find_if(
1051+
command_interfaces_.begin(), command_interfaces_.end(), [&](auto & interface)
1052+
{ return (interface.get_name() == params_.speed_scaling.command_interface); });
1053+
if (it != command_interfaces_.end())
1054+
{
1055+
scaling_command_interface_ = *it;
1056+
}
1057+
else
1058+
{
1059+
RCLCPP_ERROR(
1060+
logger, "Did not find speed scaling interface '%s' in command interfaces.",
1061+
params_.speed_scaling.command_interface.c_str());
1062+
return CallbackReturn::ERROR;
1063+
}
1064+
}
1065+
9681066
// order all joints in the storage
9691067
for (const auto & interface : params_.command_interfaces)
9701068
{
@@ -1159,6 +1257,7 @@ void JointTrajectoryController::publish_state(
11591257
{
11601258
state_publisher_->msg_.output = command_current_;
11611259
}
1260+
state_publisher_->msg_.speed_scaling_factor = scaling_factor_;
11621261

11631262
state_publisher_->unlockAndPublish();
11641263
}
@@ -1653,6 +1752,40 @@ void JointTrajectoryController::resize_joint_trajectory_point_command(
16531752
}
16541753
}
16551754

1755+
bool JointTrajectoryController::set_scaling_factor(double scaling_factor)
1756+
{
1757+
if (scaling_factor < 0)
1758+
{
1759+
RCLCPP_WARN(
1760+
get_node()->get_logger(),
1761+
"Scaling factor has to be greater or equal to 0.0 - Ignoring input!");
1762+
return false;
1763+
}
1764+
1765+
if (scaling_factor != scaling_factor_.load())
1766+
{
1767+
RCLCPP_INFO(
1768+
get_node()->get_logger().get_child("speed_scaling"), "New scaling factor will be %f",
1769+
scaling_factor);
1770+
}
1771+
scaling_factor_.store(scaling_factor);
1772+
if (
1773+
params_.speed_scaling.command_interface.empty() &&
1774+
!params_.speed_scaling.state_interface.empty())
1775+
{
1776+
RCLCPP_WARN_ONCE(
1777+
get_node()->get_logger(),
1778+
"Setting the scaling factor while only one-way communication with the hardware is setup. "
1779+
"This will likely get overwritten by the hardware again. If available, please also setup "
1780+
"the speed_scaling_command_interface_name");
1781+
}
1782+
else
1783+
{
1784+
scaling_factor_cmd_.store(scaling_factor);
1785+
}
1786+
return true;
1787+
}
1788+
16561789
bool JointTrajectoryController::has_active_trajectory() const
16571790
{
16581791
return current_trajectory_ != nullptr && current_trajectory_->has_trajectory_msg();

0 commit comments

Comments
 (0)