fix r2d2.urdf and avoid self-penetrating limbs
This commit is contained in:
@@ -11,7 +11,7 @@
|
|||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.6" radius="0.2"/>
|
<cylinder length="0.6" radius="0.17"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
@@ -266,7 +266,7 @@
|
|||||||
<joint name="left_gripper_joint" type="revolute">
|
<joint name="left_gripper_joint" type="revolute">
|
||||||
<axis xyz="0 0 1"/>
|
<axis xyz="0 0 1"/>
|
||||||
<limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>
|
<limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>
|
||||||
<origin rpy="0 0 0" xyz="0.2 0.01 0"/>
|
<origin rpy="0 0 0" xyz="0.2 0.02 0"/>
|
||||||
<parent link="gripper_pole"/>
|
<parent link="gripper_pole"/>
|
||||||
<child link="left_gripper"/>
|
<child link="left_gripper"/>
|
||||||
</joint>
|
</joint>
|
||||||
@@ -317,7 +317,7 @@
|
|||||||
<joint name="right_gripper_joint" type="revolute">
|
<joint name="right_gripper_joint" type="revolute">
|
||||||
<axis xyz="0 0 -1"/>
|
<axis xyz="0 0 -1"/>
|
||||||
<limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>
|
<limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>
|
||||||
<origin rpy="0 0 0" xyz="0.2 -0.01 0"/>
|
<origin rpy="0 0 0" xyz="0.2 -0.02 0"/>
|
||||||
<parent link="gripper_pole"/>
|
<parent link="gripper_pole"/>
|
||||||
<child link="right_gripper"/>
|
<child link="right_gripper"/>
|
||||||
</joint>
|
</joint>
|
||||||
@@ -368,13 +368,13 @@
|
|||||||
<link name="head">
|
<link name="head">
|
||||||
<visual>
|
<visual>
|
||||||
<geometry>
|
<geometry>
|
||||||
<sphere radius="0.2"/>
|
<sphere radius="0.16"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="white"/>
|
<material name="white"/>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<geometry>
|
<geometry>
|
||||||
<sphere radius="0.2"/>
|
<sphere radius="0.16"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
@@ -412,7 +412,7 @@
|
|||||||
<joint name="tobox" type="fixed">
|
<joint name="tobox" type="fixed">
|
||||||
<parent link="head"/>
|
<parent link="head"/>
|
||||||
<child link="box"/>
|
<child link="box"/>
|
||||||
<origin xyz="0 0.1414 0.1414"/>
|
<origin xyz="0 0.1214 0.1214"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|||||||
Reference in New Issue
Block a user