You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
Hi!
I think that the on-path soft-stop is a very important functionality for any manipulator. Since the speed scaling came out in rolling I thought I could leverage that to implement a soft-stop, but I fear that a ramp-down that is sent with a burst of messages could suffer from latency and not be reliable enough in industrial applications. I'd rather have the joint_trajectory_controller handle the ramp-down.
There are several decisions to make, and I tried to turn them into requisites. For each I give my opinion, which corresponds to the way it's done in the sample implementation below.
REQUISITES:
Ramp down shape? Linear, sinusoid, quintic? I'd go with sinusoid
Should the goal be kept "active" on soft stop (pause function)? I think so, we shouldn't terminate the active goal or this functionality would be a controlled cancel/abort. The cancel can be issued by the application upon receiving the stopped status.
Speed scaling works only on position command interface, then should the soft stop apply to position command interface only too? I think so, for the same good reasons that are valid for the speed scaling. The soft stop could use other mechanisms to make it work anyway, but only if it actually makes sense and is reliable.
Should we use the speed scaling logic directly or should we implement a parallel/similar logic? How would they interact? I think the stop logic should have its own logic and should add to the speed scaling by further tuning the speed, as they are separate concerns.
Soft stop should be applied/applicable also on on-robot scaling? I think so, but only if there's no velocity command_interface, otherwise we'd have to use a separate mechanism.
What if a cancel/abort/preempt arrives during soft stop? Since the soft stop keeps the goal active then we just apply the standard behavior and apply the incoming action to an active goal as usual
What happens if a new speed scaling factor is issued during soft stop? I'd apply it cumulatively
What's the default soft stop time? Ideally, I'd calculate the minimum possible given the current joint acceleration/jerk limits, if available. But JTC doesn't read robot's limits if I'm not wrong. The user should still be able to set a custom stop time per-call, so he can handle the stop time to respect robot limits. I'll go with a default ramp-down duration and a selectable ramp-down in the command.
Soft stop can't be partial, it's either 0 or 1. If the target is not 0, then is automatically set to 1. This is not to overlap with speed scaling logic and scope
What to do if the soft-stop command arrives when the time remaining to complete the traj shorter than the ramp-down time? I'd keep the original traj and hold it at the last point keeping the goal active instead of ramping it down with soft stop. I think this makes the behavior more predictable and avoids very slow movements at the end of the traj so it's worth it, even if it adds a little bit of complexity. Quite an edge case though.
What to do if the soft-stop command arrives when the JTC is already stopping? My strategy: if the ramp-down duration is the same then we ignore. If the ramp-down duration changes then we treat it as a new stop command issued and recompute the ramp depending on the new duration. Same goes for restarts (if a restart command is issued while already restarting). If we don't ignore repeated commands then if the frequency is high enough we'd keep delaying the ramp-down and the motion wouldn't actually perform a stop. Maybe it's not a problem so relevant, but I think its more adherent to what I'd expect from stop/start buttons on a robot
What if a restart is issued while stopping? I think we just compute resume the ramp from the current stop scaling factor. Same goes if a stop is issued while restarting. Smooth and lightweight and respects a intuitive behavior
DESIGN CHOICHES
Very briefly, there are obviously A LOT of choices to do while designing such a functionality. In general I tried keep it as low-impact as I could and avoid breaking API/ABI as I could. I focused on a controller‑side pause/resume that minimizes changes to existing interfaces and I avoided introducing new message types. The soft‑stop is implemented as a time‑scaling factor much like speed scaling functionality, so the path is preserved. ROS API is additive (new topics + param); C++ ABI changes are unavoidable because JTC class layout changes, but let me know if you'd have better solutions.
Commands are issued through ~/soft_stop topic and execution state is read from ~/soft_stop_state topic, both using control_msgs/InterfaceValue (to avoid introducing a new message type).
Right now since only rolling and kilted branches have the implementation for both speed scaling and soft-stop, in jazzy I matched the implementation for humble. There's currently a PR about backporting speed scaling to Jazzy but is't not approved yet. It wouldn't be a problem to modify jazzy's soft stop to adapt to the speed scaling feature.
Before going in depth on design choices, I'd need to understand if this feature is desired and if the requisites are aligned. Otherwise there'd be much to rewrite anyway.
SAMPLE IMPLEMENTATION
I made a working implementation in humble, jazzy, kilted and rolling, you can get them in my fork of ros2_controllers on the branches named soft-stop-${ROS_DISTRO}, except for rolling where the branch is named soft-stop-master.
So to clone them:
If you test it with other launchers you'll have to change the topic names accordingly.
Since CLI commands tend to be slow and it's hard to test well, especially on real robots, I modified a little hmi I use for other projects. You find it in the soft-stop branch of THIS REPO. Please note that the reset button does nothing useful for soft-stop, only START and STOP buttons work.
To start the HMI with the same example as above (change the topic names if needed), but please note that I tested it only on jazzy:
The soft-stop-* branches build correctly in the docker container of ros2_control_ci relative to each distro.
I added tests for the core requisites above. The test coverage is not complete, I think it's enough for an initial validation but should be extended if this goes on: I can detail the coverage if/when needed. colcon test finishes correctly on all distros, and I used pre-commit before pushing the changes on all distros.
Other than the Panda demo above, which I tested in Humble and Jazzy, in all distros I used some basic examples of JTC to verify the functionalities. In Humble and Jazzy I also tested the commands on a real Ufactory Lite6 robot.
PRACTICAL CONSEQUENCES FOR CURRENT IMPLEMENTATION
Since MoveIt currently keeps track of the execution time by default, using soft stop with MoveIt will make the trajectory fail if the stop isn't really short. I see there are params to avoid checking duration or to extend the tolerance but I'm not sure if they are used.
In my ManyMove I track the execution time too, but I can update that behavior quite easily. I use MoveIt for planning and JTC directly for execution, so for me adapting to this change is quite quick. I can try and check how this can be handled in MoveIt too if this moves on.
On the bright side, soft-stop would still remain an optional functionality: everything works as before and there are no behavioral changes if the user doesn't use soft-stop.
Hi!
I think that the on-path soft-stop is a very important functionality for any manipulator. Since the speed scaling came out in rolling I thought I could leverage that to implement a soft-stop, but I fear that a ramp-down that is sent with a burst of messages could suffer from latency and not be reliable enough in industrial applications. I'd rather have the joint_trajectory_controller handle the ramp-down.
There are several decisions to make, and I tried to turn them into requisites. For each I give my opinion, which corresponds to the way it's done in the sample implementation below.
REQUISITES:
DESIGN CHOICHES
Very briefly, there are obviously A LOT of choices to do while designing such a functionality. In general I tried keep it as low-impact as I could and avoid breaking API/ABI as I could. I focused on a controller‑side pause/resume that minimizes changes to existing interfaces and I avoided introducing new message types. The soft‑stop is implemented as a time‑scaling factor much like speed scaling functionality, so the path is preserved. ROS API is additive (new topics + param); C++ ABI changes are unavoidable because JTC class layout changes, but let me know if you'd have better solutions.
Commands are issued through
~/soft_stoptopic and execution state is read from~/soft_stop_statetopic, both using control_msgs/InterfaceValue (to avoid introducing a new message type).Right now since only
rollingandkiltedbranches have the implementation for both speed scaling and soft-stop, injazzyI matched the implementation forhumble. There's currently a PR about backporting speed scaling to Jazzy but is't not approved yet. It wouldn't be a problem to modifyjazzy's soft stop to adapt to the speed scaling feature.Before going in depth on design choices, I'd need to understand if this feature is desired and if the requisites are aligned. Otherwise there'd be much to rewrite anyway.
SAMPLE IMPLEMENTATION
I made a working implementation in humble, jazzy, kilted and rolling, you can get them in my fork of ros2_controllers on the branches named
soft-stop-${ROS_DISTRO}, except for rolling where the branch is namedsoft-stop-master.So to clone them:
git clone https://github.com/pastoriomarco/ros2_controllers -b soft-stop-${ROS_DISTRO}Example STOP/START commands (Jazzy):
The following commands work for the controller's topic generated by
moveit_resources_panda_moveit_configdemo. I tested it extensively in jazzy:To launch the
moveit_resources_panda_moveit_configdemo:If you test it with other launchers you'll have to change the topic names accordingly.
Since CLI commands tend to be slow and it's hard to test well, especially on real robots, I modified a little hmi I use for other projects. You find it in the
soft-stopbranch of THIS REPO. Please note that the reset button does nothing useful for soft-stop, only START and STOP buttons work.To start the HMI with the same example as above (change the topic names if needed), but please note that I tested it only on jazzy:
Screencast.from.2026-01-21.11-30-13.webm
BUILD AND TESTS
The
soft-stop-*branches build correctly in the docker container of ros2_control_ci relative to each distro.I added tests for the core requisites above. The test coverage is not complete, I think it's enough for an initial validation but should be extended if this goes on: I can detail the coverage if/when needed.
colcon testfinishes correctly on all distros, and I used pre-commit before pushing the changes on all distros.Other than the Panda demo above, which I tested in Humble and Jazzy, in all distros I used some basic examples of JTC to verify the functionalities. In Humble and Jazzy I also tested the commands on a real Ufactory Lite6 robot.
PRACTICAL CONSEQUENCES FOR CURRENT IMPLEMENTATION
Since MoveIt currently keeps track of the execution time by default, using soft stop with MoveIt will make the trajectory fail if the stop isn't really short. I see there are params to avoid checking duration or to extend the tolerance but I'm not sure if they are used.
In my ManyMove I track the execution time too, but I can update that behavior quite easily. I use MoveIt for planning and JTC directly for execution, so for me adapting to this change is quite quick. I can try and check how this can be handled in MoveIt too if this moves on.
On the bright side, soft-stop would still remain an optional functionality: everything works as before and there are no behavioral changes if the user doesn't use soft-stop.