diff --git a/ur_moveit_config/config/moveit_controllers.yaml b/ur_moveit_config/config/moveit_controllers.yaml index a55d0d486..57e276b7f 100644 --- a/ur_moveit_config/config/moveit_controllers.yaml +++ b/ur_moveit_config/config/moveit_controllers.yaml @@ -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: diff --git a/ur_moveit_config/doc/index.rst b/ur_moveit_config/doc/index.rst index d23eefa9b..7d2ad19e1 100644 --- a/ur_moveit_config/doc/index.rst +++ b/ur_moveit_config/doc/index.rst @@ -23,3 +23,21 @@ interaction using Now you should be able to use the MoveIt Plugin in rviz2 to plan and execute trajectories with the robot as explained `here `_. + +.. note:: + 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 + :start-at: trajectory_execution: + :end-at: execution_duration_monitoring + :caption: moveit_controllers.yaml diff --git a/ur_robot_driver/doc/usage/move.rst b/ur_robot_driver/doc/usage/move.rst index 6abe1bf6e..e51b6c7fe 100644 --- a/ur_robot_driver/doc/usage/move.rst +++ b/ur_robot_driver/doc/usage/move.rst @@ -67,4 +67,16 @@ To test the driver with the example MoveIt-setup, first start the driver as desc Now you should be able to use the MoveIt Plugin in rviz2 to plan and execute trajectories with the robot as explained `here `_. +.. note:: + 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`.