Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Moves finger collision geometries to the finger joints #151

Closed
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
34 changes: 20 additions & 14 deletions franka_description/robots/hand.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -33,39 +33,45 @@
<sphere radius="${0.04+safety_distance}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0 0.1" rpy="0 ${pi/2} ${pi/2}"/>
</link>
<link name="${ns}_leftfinger">
<visual>
<geometry>
<cylinder radius="${0.02+safety_distance}" length="0.1" />
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</collision>
</visual>
<collision>
<origin xyz="0 -0.05 0.1" rpy="0 0 0"/>
<origin xyz="0 0.01 0.0415" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.02+safety_distance}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0.05 0.1" rpy="0 0 0"/>
<origin xyz="0 -0.015 0.0416" rpy="0 ${pi/2} ${pi/2}"/>
<geometry>
<sphere radius="${0.02+safety_distance}" />
<cylinder radius="${0.02+safety_distance}" length="0.05" />
</geometry>
</collision>
</link>
<link name="${ns}_leftfinger">
<visual>
<geometry>
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
</link>
<link name="${ns}_rightfinger">
<visual>
<origin xyz="0 0 0" rpy="0 0 ${pi}"/>
<geometry>
<mesh filename="package://franka_description/meshes/visual/finger.dae"/>
</geometry>
</visual>
<collision>
<origin xyz="0 -0.01 0.0415" rpy="0 0 0"/>
<geometry>
<sphere radius="${0.02+safety_distance}" />
</geometry>
</collision>
<collision>
<origin xyz="0 0.015 0.0416" rpy="0 ${pi/2} ${pi/2}"/>
<geometry>
<cylinder radius="${0.02+safety_distance}" length="0.05" />
</geometry>
</collision>
</link>
<joint name="${ns}_finger_joint1" type="prismatic">
<parent link="${ns}_hand"/>
Expand Down