Skip to content
Snippets Groups Projects
Commit 4ca99f9e authored by Florian Walch's avatar Florian Walch
Browse files

Avoid MoveIt timeouts for gripper

parent 344534c1
No related branches found
No related tags found
No related merge requests found
......@@ -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
......
......@@ -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>
......
......@@ -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]
......@@ -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
......@@ -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 -->
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment