From 544ee6c4b4f698b46772d70f2947bbacd1daddc4 Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Tue, 8 Oct 2024 20:52:40 +0200 Subject: [PATCH] [moveit] Add config for trajectory execution and disable execution monitoring by default With the scaled JTC execution time monitoring doesn't make much sense as long as MoveIt is not aware of the trajectory scaling. --- ur_moveit_config/config/moveit_controllers.yaml | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/ur_moveit_config/config/moveit_controllers.yaml b/ur_moveit_config/config/moveit_controllers.yaml index 34e4194c7..a55d0d486 100644 --- a/ur_moveit_config/config/moveit_controllers.yaml +++ b/ur_moveit_config/config/moveit_controllers.yaml @@ -1,6 +1,12 @@ # MoveIt uses this configuration for controller management moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager +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 + moveit_simple_controller_manager: controller_names: - scaled_joint_trajectory_controller