mirror of
https://github.com/osrf/gazebo_models.git
synced 2025-09-15 12:58:56 +08:00
fix simple arm simple gripper model
This commit is contained in:
parent
af301c5e96
commit
bcca3bb67f
@ -7,6 +7,7 @@
|
|||||||
|
|
||||||
<include>
|
<include>
|
||||||
<uri>model://simple_gripper</uri>
|
<uri>model://simple_gripper</uri>
|
||||||
|
<pose>1.8 0 1 0 0 0</pose>
|
||||||
</include>
|
</include>
|
||||||
|
|
||||||
<plugin name="simple_arm_plugin" filename="libJointTrajectoryPlugin.so"/>
|
<plugin name="simple_arm_plugin" filename="libJointTrajectoryPlugin.so"/>
|
||||||
|
|||||||
@ -9,7 +9,7 @@
|
|||||||
<collision name="collision">
|
<collision name="collision">
|
||||||
<geometry>
|
<geometry>
|
||||||
<box>
|
<box>
|
||||||
<size>0.2 0.2 1.0</size>
|
<size>0.05 0.05 1.0</size>
|
||||||
</box>
|
</box>
|
||||||
</geometry>
|
</geometry>
|
||||||
<surface>
|
<surface>
|
||||||
@ -23,7 +23,7 @@
|
|||||||
<visual name="visual">
|
<visual name="visual">
|
||||||
<geometry>
|
<geometry>
|
||||||
<box>
|
<box>
|
||||||
<size>0.2 0.2 1.0</size>
|
<size>0.05 0.05 1.0</size>
|
||||||
</box>
|
</box>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material>
|
<material>
|
||||||
@ -249,14 +249,6 @@
|
|||||||
<xyz>0 0 1</xyz>
|
<xyz>0 0 1</xyz>
|
||||||
</axis>
|
</axis>
|
||||||
</joint>
|
</joint>
|
||||||
<joint name="fixed_riser" type="revolute">
|
|
||||||
<child>riser</child>
|
|
||||||
<parent>world</parent>
|
|
||||||
<axis>
|
|
||||||
<limit><lower>0</lower><upper>0</upper></limit>
|
|
||||||
<xyz>0 0 1</xyz>
|
|
||||||
</axis>
|
|
||||||
</joint>
|
|
||||||
|
|
||||||
<gripper name="simple_gripper">
|
<gripper name="simple_gripper">
|
||||||
<grasp_check>
|
<grasp_check>
|
||||||
|
|||||||
Loading…
Reference in New Issue
Block a user