From 4ca99f9e3374263e1f21cb86907d04680a4f8e1d Mon Sep 17 00:00:00 2001 From: Florian Walch <florian.walch@franka.de> Date: Mon, 19 Mar 2018 11:54:46 +0100 Subject: [PATCH] Avoid MoveIt timeouts for gripper --- CHANGELOG.md | 2 +- franka_description/robots/hand.xacro | 4 ++-- franka_gripper/config/franka_gripper_node.yaml | 2 +- panda_moveit_config/config/joint_limits.yaml | 10 ++++++++++ .../launch/trajectory_execution.launch.xml | 2 +- 5 files changed, 15 insertions(+), 5 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index a576401..0dcc9fc 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -12,7 +12,7 @@ * Add `load_gripper` argument (default: `true`) to `panda_moveit.launch` * Conditionally load controllers/SRDFs based on `load_gripper` * Add gripper controller configuration (requires running `franka_gripper_node`) - * Added `mimic` tag for gripper fingers to URDF + * Added `mimic` tag for gripper fingers to URDF and fixed velocity limits ## 0.3.0 - 2018-02-22 diff --git a/franka_description/robots/hand.xacro b/franka_description/robots/hand.xacro index c00ef1a..1cd3777 100644 --- a/franka_description/robots/hand.xacro +++ b/franka_description/robots/hand.xacro @@ -51,14 +51,14 @@ <child link="${ns}_leftfinger"/> <origin xyz="0 0 0.0584" rpy="0 0 0"/> <axis xyz="0 1 0"/> - <limit effort="20" lower="0.0" upper="0.04" velocity="0.3"/> + <limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/> </joint> <joint name="${ns}_finger_joint2" type="prismatic"> <parent link="${ns}_hand"/> <child link="${ns}_rightfinger"/> <origin xyz="0 0 0.0584" rpy="0 0 0"/> <axis xyz="0 -1 0"/> - <limit effort="20" lower="0.0" upper="0.04" velocity="0.3"/> + <limit effort="20" lower="0.0" upper="0.04" velocity="0.2"/> <mimic joint="${ns}_finger_joint1" /> </joint> </xacro:macro> diff --git a/franka_gripper/config/franka_gripper_node.yaml b/franka_gripper/config/franka_gripper_node.yaml index 8799cbd..195ec8f 100644 --- a/franka_gripper/config/franka_gripper_node.yaml +++ b/franka_gripper/config/franka_gripper_node.yaml @@ -5,4 +5,4 @@ joint_names: default_speed: 0.1 # [m/s] default_grasp_epsilon: inner: 0.005 # [m] - outer: 0.005 # [m] \ No newline at end of file + outer: 0.005 # [m] diff --git a/panda_moveit_config/config/joint_limits.yaml b/panda_moveit_config/config/joint_limits.yaml index b254201..603067f 100644 --- a/panda_moveit_config/config/joint_limits.yaml +++ b/panda_moveit_config/config/joint_limits.yaml @@ -37,3 +37,13 @@ joint_limits: max_velocity: 2.871 has_acceleration_limits: false max_acceleration: 0 + panda_finger_joint1: + has_velocity_limits: true + max_velocity: 0.1 + has_acceleration_limits: false + max_acceleration: 0 + panda_finger_joint2: + has_velocity_limits: true + max_velocity: 0.1 + has_acceleration_limits: false + max_acceleration: 0 diff --git a/panda_moveit_config/launch/trajectory_execution.launch.xml b/panda_moveit_config/launch/trajectory_execution.launch.xml index b6c03c9..72906ef 100644 --- a/panda_moveit_config/launch/trajectory_execution.launch.xml +++ b/panda_moveit_config/launch/trajectory_execution.launch.xml @@ -7,7 +7,7 @@ <param name="moveit_manage_controllers" value="$(arg moveit_manage_controllers)"/> <!-- When determining the expected duration of a trajectory, this multiplicative factor is applied to get the allowed duration of execution --> - <param name="trajectory_execution/allowed_execution_duration_scaling" value="1.2"/> <!-- default 1.2 --> + <param name="trajectory_execution/allowed_execution_duration_scaling" value="1.5"/> <!-- default 1.2 --> <!-- Allow more than the expected execution time before triggering a trajectory cancel (applied after scaling) --> <param name="trajectory_execution/allowed_goal_duration_margin" value="0.5"/> <!-- default 0.5 --> <!-- Allowed joint-value tolerance for validation that trajectory's first point matches current robot state --> -- GitLab