Skip to content

Commit bf2f5f8

Browse files
authored
Merge branch 'master' into fix/motion-primitive-controller-toc
2 parents bf9c5a3 + 3e66d39 commit bf2f5f8

18 files changed

+885
-132
lines changed

.github/workflows/rolling-semi-binary-build-win.yml

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -27,5 +27,4 @@ jobs:
2727
uses: ros-controls/ros2_control_ci/.github/workflows/reusable-ros-tooling-win-build.yml@master
2828
with:
2929
ros_distro: rolling
30-
pixi_dependencies: typeguard jinja2 boost compilers octomap
31-
ninja_packages: rsl
30+
pixi_dependencies: typeguard jinja2 boost compilers octomap cpp-expected

doc/release_notes.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,6 +44,7 @@ joint_trajectory_controller
4444
don't contain velocity / acceleration information, but the trajectory does. This way, the segment
4545
up to the first waypoint will use the same interpolation as the rest of the trajectory. (`#2043
4646
<https://github.com/ros-controls/ros2_controllers/pull/2043>`_)
47+
* Added decelerate-to-stop functionality when a trajectory is canceled or preempted. Instead of immediately holding position, the controller can now smoothly decelerate each joint to a stop using the per-joint ``max_deceleration_on_cancel`` parameter. (`#2163 <https://github.com/ros-controls/ros2_controllers/pull/2163>`_)
4748

4849
pid_controller
4950
**************

joint_trajectory_controller/CMakeLists.txt

Lines changed: 1 addition & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,6 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
1818
rclcpp_lifecycle
1919
realtime_tools
2020
rsl
21-
tl_expected
2221
trajectory_msgs
2322
urdf
2423
)
@@ -37,7 +36,6 @@ generate_parameter_library(joint_trajectory_controller_parameters
3736
add_library(joint_trajectory_controller SHARED
3837
src/joint_trajectory_controller.cpp
3938
src/trajectory.cpp
40-
src/validate_jtc_parameters.cpp
4139
)
4240
target_compile_features(joint_trajectory_controller PUBLIC cxx_std_17)
4341
if(WIN32)
@@ -58,7 +56,6 @@ target_link_libraries(joint_trajectory_controller PUBLIC
5856
rclcpp_lifecycle::rclcpp_lifecycle
5957
realtime_tools::realtime_tools
6058
rsl::rsl
61-
tl_expected::tl_expected
6259
urdf::urdf
6360
angles::angles
6461
${trajectory_msgs_TARGETS}
@@ -106,7 +103,7 @@ if(BUILD_TESTING)
106103
ament_add_gmock(test_trajectory_actions
107104
test/test_trajectory_actions.cpp
108105
)
109-
set_tests_properties(test_trajectory_actions PROPERTIES TIMEOUT 300)
106+
set_tests_properties(test_trajectory_actions PROPERTIES TIMEOUT 330)
110107
target_link_libraries(test_trajectory_actions
111108
joint_trajectory_controller
112109
ros2_control_test_assets::ros2_control_test_assets)
564 KB
Loading
Lines changed: 83 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,83 @@
1+
:github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/joint_trajectory_controller/doc/decelerate_on_cancel.rst
2+
3+
.. _joint_trajectory_controller_decelerate_on_cancel:
4+
5+
Decelerate on cancel
6+
====================
7+
8+
By default, when a trajectory is canceled or preempted, the controller immediately holds the current position.
9+
This can cause problems for hardware that is moving at high velocity, as the abrupt stop may trigger faults or cause excessive wear.
10+
11+
When the ``decelerate_on_cancel`` feature is enabled, the controller instead generates a smooth stop trajectory that decelerates each joint to zero velocity using a constant deceleration profile before holding position.
12+
13+
.. image:: decelerate_hold_position.png
14+
:alt: Default behavior: immediate hold position on cancel
15+
16+
*Default behavior: the controller instantly sets the command position to the current position when a trajectory is canceled, causing an abrupt stop.*
17+
18+
.. image:: decelerate_to_stop.png
19+
:alt: Decelerate to stop behavior on cancel
20+
21+
*With decelerate on cancel enabled: the controller generates a ramped stop trajectory that smoothly decelerates each joint before holding position.*
22+
23+
How it works
24+
------------
25+
26+
When a trajectory is canceled or preempted and ``decelerate_on_cancel`` is enabled, the controller:
27+
28+
1. Reads the current velocity of each joint from the velocity state interface.
29+
2. Computes the stopping distance and time for each joint using its configured ``max_deceleration_on_cancel`` value:
30+
31+
.. math::
32+
33+
t_{stop} = \frac{|v|}{a_{max}}
34+
35+
.. math::
36+
37+
d_{stop} = \frac{v \cdot t_{stop}}{2}
38+
39+
where :math:`v` is the current velocity and :math:`a_{max}` is the configured maximum deceleration.
40+
41+
3. Generates a trajectory with intermediate waypoints that linearly ramp velocity to zero over the computed stopping time.
42+
4. Appends a final hold-position point at the computed stop position.
43+
44+
Each joint decelerates independently based on its own ``max_deceleration_on_cancel`` value, but the trajectory is synchronized so all joints finish at the same time (the slowest joint's stop time).
45+
46+
Requirements
47+
------------
48+
49+
* The hardware must provide a ``velocity`` state interface for all joints in the controller. If velocity state feedback is not available, the controller falls back to the default hold-position behavior.
50+
* Each joint must have a valid (greater than zero) ``max_deceleration_on_cancel`` value. Joints with a value of ``0.0`` cause the controller to fall back to hold-position behavior.
51+
52+
Configuration
53+
-------------
54+
55+
Enable the feature by setting ``constraints.decelerate_on_cancel`` to ``true`` and providing a ``max_deceleration_on_cancel`` value (in rad/s^2 or m/s^2) for each joint under ``constraints.<joint_name>``:
56+
57+
.. code-block:: yaml
58+
59+
controller_name:
60+
ros__parameters:
61+
joints:
62+
- joint_1
63+
- joint_2
64+
- joint_3
65+
66+
constraints:
67+
decelerate_on_cancel: true
68+
stopped_velocity_tolerance: 0.01
69+
goal_time: 0.0
70+
joint_1:
71+
max_deceleration_on_cancel: 10.0
72+
joint_2:
73+
max_deceleration_on_cancel: 3.0
74+
joint_3:
75+
max_deceleration_on_cancel: 6.0
76+
77+
.. note::
78+
79+
Both ``decelerate_on_cancel`` and ``max_deceleration_on_cancel`` are read-only parameters. They can only be set at controller configuration time and cannot be changed at runtime.
80+
81+
.. note::
82+
83+
Choose ``max_deceleration_on_cancel`` values that are within the physical limits of your hardware. Values that are too high may still cause faults, while values that are too low will result in longer stopping distances.
544 KB
Loading

joint_trajectory_controller/doc/parameters_context.yaml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
constraints:
22
Default values for tolerances if no explicit values are set in the ``JointTrajectory`` message.
3+
Also contains the ``decelerate_on_cancel`` option and per-joint ``max_deceleration_on_cancel`` values for smooth stopping behavior (see :ref:`joint_trajectory_controller_decelerate_on_cancel`).
34

45
gains: |
56
The parameters are used to configure PID loops for the ``velocity`` or ``effort``-only command interfaces. This structure contains the controller gains for every joint with following the control laws

joint_trajectory_controller/doc/userdoc.rst

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -61,6 +61,8 @@ Other features
6161

6262
* Robust to system clock changes: Discontinuous system clock changes do not cause discontinuities in the execution of already queued trajectory segments.
6363

64+
* Optional smooth deceleration on cancel: Instead of abruptly holding position, the controller can decelerate joints to a stop using configurable per-joint deceleration limits. See :ref:`joint_trajectory_controller_decelerate_on_cancel`.
65+
6466

6567
Using Joint Trajectory Controller(s)
6668
------------------------------------
@@ -209,6 +211,7 @@ Further information
209211
:titlesonly:
210212

211213
Trajectory Representation <trajectory.rst>
214+
Decelerate on cancel <decelerate_on_cancel.rst>
212215
Speed scaling <speed_scaling.rst>
213216
joint_trajectory_controller Parameters <parameters.rst>
214217
rqt_joint_trajectory_controller <../../rqt_joint_trajectory_controller/doc/userdoc.rst>

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -150,6 +150,19 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
150150
// reserved storage for result of the command when closed loop pid adapter is used
151151
std::vector<double> tmp_command_;
152152

153+
// If true, enable calculations to stop all joints using constant deceleration
154+
bool should_decelerate_on_cancel_ = false;
155+
// reserved storage for the max deceleration values
156+
std::vector<double> max_decel_;
157+
// reserved storage for each joints max stopping time
158+
std::vector<double> stop_time_;
159+
// reserved storage for each joints hold position at stop
160+
std::vector<double> hold_position_;
161+
// reserved storage for each joints stop direction
162+
std::vector<double> stop_direction_;
163+
// reserved storage for the stop trajectory
164+
std::shared_ptr<trajectory_msgs::msg::JointTrajectory> stop_trajectory_;
165+
153166
// Things around speed scaling
154167
std::atomic<double> scaling_factor_{1.0};
155168
std::atomic<double> scaling_factor_cmd_{1.0};
@@ -238,6 +251,11 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
238251
*/
239252
std::shared_ptr<trajectory_msgs::msg::JointTrajectory> set_hold_position();
240253

254+
/** @brief decelerate at constant rate to a holding position with
255+
* zero velocity and acceleration as new command
256+
*/
257+
std::shared_ptr<trajectory_msgs::msg::JointTrajectory> decelerate_to_hold_position();
258+
241259
/** @brief set last trajectory point to be repeated at success
242260
*
243261
* no matter if it has nonzero velocity or acceleration

joint_trajectory_controller/include/joint_trajectory_controller/validate_jtc_parameters.hpp

Lines changed: 72 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -20,30 +20,83 @@
2020

2121
#include "rclcpp/parameter.hpp"
2222
#include "rsl/algorithm.hpp"
23-
#include "tl_expected/expected.hpp"
23+
#include "tl/expected.hpp"
2424

2525
namespace joint_trajectory_controller
2626
{
27-
28-
/**
29-
* \brief Validate command interface type combinations for joint trajectory controller.
30-
*
31-
* \param[in] parameter The rclcpp parameter containing the command interface types.
32-
* \return tl::expected<void, std::string> An empty expected on success, or an error message on
33-
* failure.
34-
*/
3527
tl::expected<void, std::string> command_interface_type_combinations(
36-
rclcpp::Parameter const & parameter);
37-
38-
/**
39-
* \brief Validate state interface type combinations for joint trajectory controller.
40-
*
41-
* \param[in] parameter The rclcpp parameter containing the state interface types.
42-
* \return tl::expected<void, std::string> An empty expected on success, or an error message on
43-
* failure.
44-
*/
28+
rclcpp::Parameter const & parameter)
29+
{
30+
auto const & interface_types = parameter.as_string_array();
31+
32+
// Check if command interfaces combination is valid. Valid combinations are:
33+
// 1. effort
34+
// 2. velocity
35+
// 3. position [velocity, [acceleration]]
36+
// 4. position, effort
37+
38+
if (
39+
rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
40+
interface_types.size() > 1 &&
41+
!rsl::contains<std::vector<std::string>>(interface_types, "position"))
42+
{
43+
return tl::make_unexpected(
44+
"'velocity' command interface can be used either alone or 'position' "
45+
"command interface has to be present");
46+
}
47+
48+
if (
49+
rsl::contains<std::vector<std::string>>(interface_types, "acceleration") &&
50+
(!rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
51+
!rsl::contains<std::vector<std::string>>(interface_types, "position")))
52+
{
53+
return tl::make_unexpected(
54+
"'acceleration' command interface can only be used if 'velocity' and "
55+
"'position' command interfaces are present");
56+
}
57+
58+
if (
59+
rsl::contains<std::vector<std::string>>(interface_types, "effort") &&
60+
!(interface_types.size() == 1 ||
61+
(interface_types.size() == 2 &&
62+
rsl::contains<std::vector<std::string>>(interface_types, "position"))))
63+
{
64+
return tl::make_unexpected(
65+
"'effort' command interface has to be used alone or with a 'position' interface");
66+
}
67+
68+
return {};
69+
}
70+
4571
tl::expected<void, std::string> state_interface_type_combinations(
46-
rclcpp::Parameter const & parameter);
72+
rclcpp::Parameter const & parameter)
73+
{
74+
auto const & interface_types = parameter.as_string_array();
75+
76+
// Valid combinations are
77+
// 1. position [velocity, [acceleration]]
78+
79+
if (
80+
rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
81+
!rsl::contains<std::vector<std::string>>(interface_types, "position"))
82+
{
83+
return tl::make_unexpected(
84+
"'velocity' state interface cannot be used if 'position' interface "
85+
"is missing.");
86+
}
87+
88+
if (
89+
rsl::contains<std::vector<std::string>>(interface_types, "acceleration") &&
90+
(!rsl::contains<std::vector<std::string>>(interface_types, "position") ||
91+
!rsl::contains<std::vector<std::string>>(interface_types, "velocity")))
92+
{
93+
return tl::make_unexpected(
94+
"'acceleration' state interface cannot be used if 'position' and 'velocity' "
95+
"interfaces are not present.");
96+
}
97+
98+
return {};
99+
}
47100

48101
} // namespace joint_trajectory_controller
49102

0 commit comments

Comments
 (0)