-
Notifications
You must be signed in to change notification settings - Fork 479
Add decelerate to stop functionality when trajectory is canceled or preempted #2163
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Merged
Merged
Changes from all commits
Commits
Show all changes
12 commits
Select commit
Hold shift + click to select a range
ff2b850
Add decelerate to stop functionality when trajectory is canceled or p…
MarqRazz 48fbcc9
Move stop trajectory generation to trajectory.cpp
MarqRazz c9b6275
preallocate stop_trajectory variables and add test
MarqRazz 2f03ca5
revert changes to trajectory.cpp
MarqRazz 14a7c2f
Merge branch 'master' into jtc_decelerate
MarqRazz 42980df
revert test_trajectory changes
MarqRazz 6265ab5
Merge branch 'master' into jtc_decelerate
MarqRazz 06abc4a
read only parameters, velocity interface check in on_configure
MarqRazz 5d4c0fc
rename decelerate_on_cancel_ to decelerate_on_cancel_requested_
bmagyar 477bfc8
add release notes
bmagyar 6ef96cd
add decelerate on cancel documentation
bmagyar ae5b1ae
rename decelerate_on_cancel_requested_ to should_decelerate_on_cancel_
bmagyar File filter
Filter by extension
Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
There are no files selected for viewing
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
| Original file line number | Diff line number | Diff line change |
|---|---|---|
| @@ -0,0 +1,83 @@ | ||
| :github_url: https://github.com/ros-controls/ros2_controllers/blob/{REPOS_FILE_BRANCH}/joint_trajectory_controller/doc/decelerate_on_cancel.rst | ||
|
|
||
| .. _joint_trajectory_controller_decelerate_on_cancel: | ||
|
|
||
| Decelerate on cancel | ||
| ==================== | ||
|
|
||
| By default, when a trajectory is canceled or preempted, the controller immediately holds the current position. | ||
| This can cause problems for hardware that is moving at high velocity, as the abrupt stop may trigger faults or cause excessive wear. | ||
|
|
||
| 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. | ||
|
|
||
| .. image:: decelerate_hold_position.png | ||
| :alt: Default behavior: immediate hold position on cancel | ||
|
|
||
| *Default behavior: the controller instantly sets the command position to the current position when a trajectory is canceled, causing an abrupt stop.* | ||
|
|
||
| .. image:: decelerate_to_stop.png | ||
| :alt: Decelerate to stop behavior on cancel | ||
|
|
||
| *With decelerate on cancel enabled: the controller generates a ramped stop trajectory that smoothly decelerates each joint before holding position.* | ||
|
|
||
| How it works | ||
| ------------ | ||
|
|
||
| When a trajectory is canceled or preempted and ``decelerate_on_cancel`` is enabled, the controller: | ||
|
|
||
| 1. Reads the current velocity of each joint from the velocity state interface. | ||
| 2. Computes the stopping distance and time for each joint using its configured ``max_deceleration_on_cancel`` value: | ||
|
|
||
| .. math:: | ||
|
|
||
| t_{stop} = \frac{|v|}{a_{max}} | ||
|
|
||
| .. math:: | ||
|
|
||
| d_{stop} = \frac{v \cdot t_{stop}}{2} | ||
|
|
||
| where :math:`v` is the current velocity and :math:`a_{max}` is the configured maximum deceleration. | ||
|
|
||
| 3. Generates a trajectory with intermediate waypoints that linearly ramp velocity to zero over the computed stopping time. | ||
| 4. Appends a final hold-position point at the computed stop position. | ||
|
|
||
| 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). | ||
|
|
||
| Requirements | ||
| ------------ | ||
|
|
||
| * 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. | ||
| * 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. | ||
|
|
||
| Configuration | ||
| ------------- | ||
|
|
||
| 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>``: | ||
|
|
||
| .. code-block:: yaml | ||
|
|
||
| controller_name: | ||
| ros__parameters: | ||
| joints: | ||
| - joint_1 | ||
| - joint_2 | ||
| - joint_3 | ||
|
|
||
| constraints: | ||
| decelerate_on_cancel: true | ||
| stopped_velocity_tolerance: 0.01 | ||
| goal_time: 0.0 | ||
| joint_1: | ||
| max_deceleration_on_cancel: 10.0 | ||
| joint_2: | ||
| max_deceleration_on_cancel: 3.0 | ||
| joint_3: | ||
| max_deceleration_on_cancel: 6.0 | ||
|
|
||
| .. note:: | ||
|
|
||
| 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. | ||
|
|
||
| .. note:: | ||
|
|
||
| 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. |
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains hidden or bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.
Oops, something went wrong.
Add this suggestion to a batch that can be applied as a single commit.
This suggestion is invalid because no changes were made to the code.
Suggestions cannot be applied while the pull request is closed.
Suggestions cannot be applied while viewing a subset of changes.
Only one suggestion per line can be applied in a batch.
Add this suggestion to a batch that can be applied as a single commit.
Applying suggestions on deleted lines is not supported.
You must change the existing code in this line in order to create a valid suggestion.
Outdated suggestions cannot be applied.
This suggestion has been applied or marked resolved.
Suggestions cannot be applied from pending reviews.
Suggestions cannot be applied on multi-line comments.
Suggestions cannot be applied while the pull request is queued to merge.
Suggestion cannot be applied right now. Please check back later.
Uh oh!
There was an error while loading. Please reload this page.