Add decelerate to stop functionality when trajectory is canceled or preempted#2163
Add decelerate to stop functionality when trajectory is canceled or preempted#2163bmagyar merged 12 commits intoros-controls:masterfrom
Conversation
Codecov Report❌ Patch coverage is Additional details and impacted files@@ Coverage Diff @@
## master #2163 +/- ##
==========================================
+ Coverage 84.90% 85.02% +0.11%
==========================================
Files 153 153
Lines 14995 14868 -127
Branches 1290 1254 -36
==========================================
- Hits 12732 12641 -91
+ Misses 1790 1761 -29
+ Partials 473 466 -7
Flags with carried forward coverage won't be shown. Click here to find out more.
🚀 New features to boost your workflow:
|
saikishor
left a comment
There was a problem hiding this comment.
Very nice approach.
Thanks for such a nice implementation.
I've some nitpicks and comments here and there.
I'm curious to know what happens, if the declaration_on_cancel is only set for some joints of the JTC, but not all.
Thank you
joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml
Show resolved
Hide resolved
joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp
Show resolved
Hide resolved
joint_trajectory_controller/include/joint_trajectory_controller/trajectory.hpp
Outdated
Show resolved
Hide resolved
|
Hi! For what I see the decelerated stop works well, and a decelerated stop surely is a way better approach than a no-ramp hard stop. I think this feature is a must-have. It's very common in any industrial robot to have a stop functionality that ramps down with a given max acceleration for each axis. I don't know if I can do anything more than give my feedback here to help approve this PR, the code and comments look good to me. This said, if I may, the biggest problem I see here is that it's not on-path. After testing with different accelerations (even very low ones to amplify the edge cases), it's clear that this could lead to undesired effects, such as path overshoots and off-path positions. I tried to implement an on-path soft-stop function in my branch, see #2111 for details and link to code. It works on humble, jazzy, kilted and rolling, but to be honest it's not PR-ready and would need a good polish (lots of copy paste of same code structure in various parts that I'd like to refine). It would be very useful to at least understand if there's interest in merging this kind of functionality and I'll work on it (after discussing the implementation details required, obviously) |
Sorry that is not something we really have for ros2_control. We don't maintain configurations between ros2_control and other packages that use it and my companies robot configuration is private. In my first post to the PR I shared the configuration values you need to set in your control.yaml for the JTC so hopefully that made it a little easier.
This functionality is similar to a Protective or Emergency stop event except the brakes don't engage or power off the servos. This is the safest thing to do, you said stop! I can't protect users from specifying poor values for deceleration. If the trajectory requested to execute has larger accelerations than they set in the JTC which one should it choose? The user set specific settings for how to handle a cancel event shouldn't they always be applied? Technically the JTC does not enforce or validate a given trajectory against the URDF (which doesn't contain all of the joints dynamic limits) it is running on before it executes it so users are allowed to ask for things that the hardware can struggle or fail to execute. |
If any of the joints have zero values for |
Yep, it made it a lot easier indeed! The hard part was to have all compile and work together with latest(ish) rolling ros2_controller, especially MoveIt and related packages.
As I said, this functionality is simply a must-have, no doubt about it! It's one of the available modes of the protective/emergency stop in modern robots indeed. It may be ok for an emergency stop, but surely it's not something I want on a standard stop: it's not on-path, potentially risky for attached workpieces and arguably too hard on the hardware for a standard stop (depending on payload and on the tradeoff between as close to on-path as possible and softer deceleration). I tried too soft accelerations just to confirm the behavior, but even setting everything perfectly it just has several downsides for non-emergency stops. This kind of stop is actually something that I'm not using in any of my applications, not even for emergency stops, simply because I design the layout so it's never necessary to decelerate with max acceleration: simplifying, what's needed for certification is the robot to be stopped within a certain time and for it to never exit a determined area during operation. That's why I feel the need for a soft-stop function too (not instead), it's really a primary functionality of any robotic application. |
|
Is there anything else you guys would like me to address here? |
saikishor
left a comment
There was a problem hiding this comment.
Just minor comments, otherwise looks good
joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp
Outdated
Show resolved
Hide resolved
joint_trajectory_controller/src/joint_trajectory_controller.cpp
Outdated
Show resolved
Hide resolved
joint_trajectory_controller/src/joint_trajectory_controller.cpp
Outdated
Show resolved
Hide resolved
joint_trajectory_controller/src/joint_trajectory_controller.cpp
Outdated
Show resolved
Hide resolved
joint_trajectory_controller/src/joint_trajectory_controller.cpp
Outdated
Show resolved
Hide resolved
joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml
Show resolved
Hide resolved
joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml
Show resolved
Hide resolved
saikishor
left a comment
There was a problem hiding this comment.
LGTM.
Thanks for the changes. Great job 🎉
christophfroehlich
left a comment
There was a problem hiding this comment.
Overall LGTM, nice work.
- A small suggestion about variable naming.
- Please also add a release note.
Do we want to backport this to jazzy? If we do ABI break on kilted, we can also do on jazzy ;)
joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp
Outdated
Show resolved
Hide resolved
|
I think pushing this back to Jazzy would be very good! |
|
@christophfroehlich I've addressed your comments |
|
I've also stolen the content from Marq's OP and put it into a new docs page :D |
Title says it all. The old behavior of the JTC is to set the robots command position to its current pose at the time the trajectory is canceled.

For my hardware this frequently causes it to fault because it instantly sets the joints velocity to zero no matter how fast it is moving. Below is a plot of the new behavior...

I added a few parameters to the
constraintsstruct to opt into the new functionality but once the URDF supports specifying joint acceleration we could use those values if these are not specified.The new tests check for ...