-
Notifications
You must be signed in to change notification settings - Fork 408
Scaled jtc #1191
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
Scaled jtc #1191
Changes from all commits
Commits
Show all changes
76 commits
Select commit
Hold shift + click to select a range
d1fcba0
Add scaling factor to JTC
55c3bb0
use reset+initRT due to missing writeFromRT
fmauch 79a8b7c
Reformat scaling the time period
600ba71
synchronization of scaling factor with hw optional, add service for s…
c01b1ad
Improve scaling exchange with hardware
c003883
Check command interface name when setting speed scaling
aa63e5d
Update code formatting
821c88d
Do not advertise speed scaling service unless only position interface is
f7d0ae0
WIP: Adding documentation about speed scaling
71ccb39
Use a subscriber instead of a service
1fb38b8
Do not put the time_data_ into a RealtimeBuffer
6890d6e
Fix goal time violated
b5a567d
Merge remote-tracking branch 'origin/master' into scaled_jtc
908b539
Use custom message to subscribe speed scaling
1e66e44
Add scaling factor to controller state
7daf240
Code formatting
66abfd9
Allow scaling factors greater than 1
45fa036
Add parameter validator for default scaling factor
5e9592b
More formatting...
42394b9
Remove unnecessary iostream include
ba5fecb
REVERT_ME: Use dev branch for control_msgs
4b2f18c
Write back scaling factor to buffer when updated from hardware
76e5cab
Remove additional time_data structure in update method
b22ce07
Use std::atomic for scaling factor buff
7e88744
Use transient_local for the speed scaling topic subscriber
d2130e0
Added documentation on tolerance effects
915bfd3
Added a short explanation of scaling
90c6d45
Use a ordering-safe reference for scaling command and state interfaces
77e78ce
Merge branch 'master' into scaled_jtc
0a3b974
REVERT_ME Use my version of control_msgs
09bea48
Use period directly instead of calculating an own period
9658347
Merge branch 'master' into scaled_jtc
0dba992
Set update rate in testing controller
a96dd54
Tests: Call controller.configure() instead of controller.get_node().c…
d55fea7
Sample trajectory at point t+dT
9400838
Update trajectory_controller_tests
777e5a9
Merge branch 'master' into jtc_tdt
62003f8
Fix period calculation in trajectory_actions test
1f9bfb4
Sample trajectory based on the sum of periods instead of the absolute…
adc270f
Merge branch 'jtc_sum_periods' into scaled_jtc
0d08c38
Cleanup some logging
35dbc4f
Merge remote-tracking branch 'origin/master' into scaled_jtc_merged
fmauch c56ce2b
Add test for scaled trajectory execution
fmauch b395104
Merge remote-tracking branch 'origin/master' into scaled_jtc
fmauch b101360
Use master branch of control_msgs repo
christophfroehlich 21c9c4d
Apply suggestions from code review
fmauch 9d5c981
Update tolerances documentation
fmauch a2d319b
Only log set scaling factor if it is changed
fmauch 5d2b852
Remove duplicate reading period from parameter
fmauch 7844221
Make trajectory test use tolerances
fmauch a74f94d
Check goal tolerance from error to next command
fmauch 57ec2a5
Add a test that verifies that the JTC samples the trajectory correctly
fmauch 0b760bc
Fix goal constraint specifications in test
fmauch d141556
Merge remote-tracking branch 'origin/master' into scaled_jtc
fmauch 2abc954
Adding some tests for setting the speed scaling factor
fmauch 94d851a
Merge remote-tracking branch 'origin/master' into scaled_jtc
fmauch 06c3dd7
Add tests using speed_scaling hardware interfaces
fmauch 6505a1f
Merge branch 'master' into scaled_jtc
destogl 8fd9467
Merge remote-tracking branch 'origin/master' into scaled_jtc
fmauch 31f9a6a
Update missing change
fmauch 35d0d24
Fix spelling mistake in docs
fmauch c538d01
Merge remote-tracking branch 'origin/master' into scaled_jtc
fmauch fc26f88
Merge remote-tracking branch 'origin/master' into scaled_jtc
fmauch c7955f8
Code formatting
fmauch 402ebca
Cleanup some merge errors
fmauch d1fde60
Removed unnecessary line
fmauch 76411c5
Merge branch 'master' into scaled_jtc
christophfroehlich 6c886b5
Apply suggestions from code review
fmauch ddf5724
Add API documentation for set_scaling_factor
fmauch 76a9261
Use hierarchical parameter naming
fmauch 38e0ff3
Remove unnecessary check for ACTIVE
fmauch e0fff8d
fix parameter loading in tests
fmauch 35a0cc5
Merge branch 'master' into scaled_jtc
fmauch 06a159e
Add release notes about speed scaling
fmauch 2515c2a
Correct method docstring
fmauch c839c94
Clarified documentation when on-robot scaling can be used
fmauch 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
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,110 @@ | ||
.. _jtc_speed_scaling: | ||
|
||
Speed scaling | ||
============= | ||
|
||
The ``joint_trajectory_controller`` (JTC) supports dynamically scaling its trajectory execution speed. | ||
That means, when specifying a scaling factor :math:`{f}` of less than 1, execution will proceed only | ||
:math:`{f \cdot \Delta_t}` per control step where :math:`{\Delta_t}` is the controller's cycle time. | ||
|
||
Methods of speed scaling | ||
------------------------ | ||
|
||
Generally, the speed scaling feature has two separate scaling approaches in mind: On-Robot scaling | ||
and On-Controller scaling. They are both conceptually different and to correctly configure speed | ||
scaling it is important to understand the differences. | ||
|
||
On-Robot speed scaling | ||
~~~~~~~~~~~~~~~~~~~~~~ | ||
|
||
This scaling method is intended for robots that provide a scaling feature directly on the robot's | ||
teach pendant and / or through a safety feature. One example of such robots are the `Universal | ||
Robots manipulators <https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver>`_. | ||
|
||
The hardware interface needs to report the speed scaling through a state interface so it can be | ||
read by the controller. Optionally, a command interface for setting the speed scaling value on the | ||
hardware can be provided (if applicable) in order to set speed scaling through a ROS topic. | ||
|
||
For the scope of this documentation a user-defined scaling and a safety-limited scaling will be | ||
treated the same resulting in a "hardware scaling factor". | ||
|
||
In this setup, the hardware will treat the command sent from the ROS controller (e.g. Reach joint | ||
configuration :math:`{\theta}` within :math:`{\Delta_t}` seconds.). This effectively means that the | ||
robot will only make half of the way towards the target configuration when a scaling factor of 0.5 | ||
is given (neglecting acceleration and deceleration influences during this time period). | ||
|
||
The following plot shows trajectory execution (for one joint) with a hardware-scaled execution and | ||
a controller that is **not** aware of speed scaling: | ||
|
||
.. image:: traj_without_speed_scaling.png | ||
:alt: Trajectory with a hardware-scaled-down execution with a non-scaled controller | ||
|
||
The graph shows a trajectory with one joint being moved to a target point and back to its starting | ||
point. As the joint's speed is limited to a very low setting on the teach pendant, speed scaling | ||
(black line) activates and limits the joint speed (green line). As a result, the target trajectory | ||
(light blue) doesn't get executed by the robot, but instead the pink trajectory is executed. The | ||
vertical distance between the light blue line and the pink line is the path error in each control | ||
cycle. We can see that the path deviation gets above 300 degrees at some point and the target point | ||
at -6 radians never gets reached. | ||
|
||
With the scaled version of the trajectory controller the example motion shown in the previous diagram becomes: | ||
|
||
.. image:: traj_with_speed_scaling.png | ||
:alt: Trajectory with a hardware-scaled-down execution with a scaled controller | ||
|
||
The deviation between trajectory interpolation on the ROS side and actual robot execution stays | ||
minimal and the robot reaches the intermediate setpoint instead of returning "too early" as in the | ||
example above. | ||
|
||
Scaling is done in such a way, that the time in the trajectory is virtually scaled. For example, if | ||
a controller runs with a cycle time of 100 Hz, each control cycle is 10 ms long. A speed scaling of | ||
0.5 means that in each time step the trajectory is moved forward by 5 ms instead. | ||
So, the beginning of the 3rd timestep is 15 ms instead of 30 ms in the trajectory. | ||
|
||
Command sampling is performed as in the unscaled case, with the timestep's start plus the **full** | ||
cycle time of 10 ms. The robot will scale down the motion command by 50% resulting in only half of | ||
the distance being executed, which is why the next control cycle will be started at the current | ||
start plus half of the step time. | ||
|
||
|
||
On-Controller speed scaling | ||
~~~~~~~~~~~~~~~~~~~~~~~~~~~ | ||
|
||
Conceptually, with this scaling the robot hardware isn't aware of any scaling happening. The JTC | ||
generates commands to be sent to the robot that are already scaled down accordingly, so they can be | ||
directly executed by the robot. | ||
|
||
Since the hardware isn't aware of speed scaling, the speed-scaling related command and state | ||
interfaces should not be specified and the scaling factor will be set through the | ||
``~/speed_scaling_input`` topic directly: | ||
|
||
.. code:: console | ||
|
||
$ ros2 topic pub --qos-durability transient_local --once \ | ||
/joint_trajectory_controller/speed_scaling_input control_msgs/msg/SpeedScalingFactor "{factor: 0.5}" | ||
|
||
|
||
.. note:: | ||
The ``~/speed_scaling_input`` topic uses the QoS durability profile ``transient_local``. This | ||
means you can restart the controller while still having a publisher on that topic active. | ||
|
||
.. note:: | ||
The current implementation only works for position-based interfaces. | ||
|
||
fmauch marked this conversation as resolved.
Show resolved
Hide resolved
|
||
|
||
Effect on tolerances | ||
-------------------- | ||
|
||
When speed scaling is used while executing a trajectory, the tolerances configured for execution | ||
will be scaled, as well. | ||
|
||
Since commands are generated from the scaled trajectory time, **path errors** will also be compared | ||
to the scaled trajectory. | ||
|
||
The **goal time tolerance** also uses the virtual trajectory time. This means that a trajectory | ||
being executed with a constant scaling factor of 0.5 will take twice as long for execution than the | ||
``time_from_start`` value of the last trajectory point specifies. As long as the robot doesn't take | ||
longer than that the goal time tolerance is considered to be met. | ||
|
||
If an application relies on the actual execution time as set in the ``time_from_start`` fields, an | ||
external monitoring has to be wrapped around the trajectory execution action. |
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
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.