Skip to content

Commit

Permalink
Update formatting and config file comment
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch committed Oct 9, 2024
1 parent bf24ed4 commit d5a1822
Show file tree
Hide file tree
Showing 3 changed files with 21 additions and 9 deletions.
2 changes: 1 addition & 1 deletion ur_moveit_config/config/moveit_controllers.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ trajectory_execution:
allowed_execution_duration_scaling: 1.2
allowed_goal_duration_margin: 0.5
allowed_start_tolerance: 0.01
execution_duration_monitoring: false # Not much use when using the scaled JTC
execution_duration_monitoring: false # May lead to unexpectedly aborted goals with scaled JTC

moveit_simple_controller_manager:
controller_names:
Expand Down
13 changes: 10 additions & 3 deletions ur_moveit_config/doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,16 @@ Now you should be able to use the MoveIt Plugin in rviz2 to plan and execute tra
robot as explained `here <https://moveit.picknik.ai/main/doc/tutorials/quickstart_in_rviz/quickstart_in_rviz_tutorial.html>`_.

.. note::
The MoveIt configuration provided here has Trajectory Execution Monitoring *disabled*, as the Scaled Joint Trajectory Controller may cause trajectories to be executed at a lower velocity than they were originally planned by MoveIt. MoveIt's TEM however is not aware of this deliberate slow-down due to scaling and will in most cases unnecessarily (and unexpectedly) abort goals.

Until this incompatibility is resolved, the default value for `execution_duration_monitoring` is set to `false`. Users who wish to temporarily (re)enable TEM at runtime (for use with other, non-scaling controllers) can do so using the ROS 2 parameter services supported by MoveIt.
The MoveIt configuration provided here has Trajectory Execution Monitoring (TEM) *disabled*, as the
Scaled Joint Trajectory Controller may cause trajectories to be executed at a lower velocity
than they were originally planned by MoveIt. MoveIt's TEM however is not aware of this
deliberate slow-down due to scaling and will in most cases unnecessarily (and unexpectedly)
abort goals.

Until this incompatibility is resolved, the default value for ``execution_duration_monitoring``
is set to ``false``. Users who wish to temporarily (re)enable TEM at runtime (for use with
other, non-scaling controllers) can do so using the ROS 2 parameter services supported by
MoveIt.

.. literalinclude:: ../config/moveit_controllers.yaml
:language: yaml
Expand Down
15 changes: 10 additions & 5 deletions ur_robot_driver/doc/usage/move.rst
Original file line number Diff line number Diff line change
Expand Up @@ -68,10 +68,15 @@ Now you should be able to use the MoveIt Plugin in rviz2 to plan and execute tra
robot as explained `here <https://moveit.picknik.ai/main/doc/tutorials/quickstart_in_rviz/quickstart_in_rviz_tutorial.html>`_.

.. note::
Usually, MoveIt uses trajectory execution monitoring (TEM). If executing a trajectory takes too long,
e.g. because the action server died or the robot is blocked, this will lead to an error in
trajectory execution. However, this isn't necessarily compatible with the scaled joint
trajectory controller (as long as TEM is not aware of the scaling), as execution time can
be unbounded on purpose. Hence, TEM is disabled in the example MoveIt configuration.
The MoveIt configuration provided here has Trajectory Execution Monitoring (TEM) *disabled*, as the
Scaled Joint Trajectory Controller may cause trajectories to be executed at a lower velocity
than they were originally planned by MoveIt. MoveIt's TEM however is not aware of this
deliberate slow-down due to scaling and will in most cases unnecessarily (and unexpectedly)
abort goals.

Until this incompatibility is resolved, the default value for ``execution_duration_monitoring``
is set to ``false``. Users who wish to temporarily (re)enable TEM at runtime (for use with
other, non-scaling controllers) can do so using the ROS 2 parameter services supported by
MoveIt.

For more details, please see :ref:`ur_moveit_config`.

0 comments on commit d5a1822

Please sign in to comment.