mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-15 06:00:12 +00:00
8a265b8af2
finish much better C++ vrSyncPlugin, running in-the-loop with the physics at high frequency, see also vr_kuka_setup_vrSyncPlugin.py
150 lines
3.9 KiB
XML
150 lines
3.9 KiB
XML
<?xml version="1.0"?>
|
|
<robot name="physics">
|
|
<link name="gripper_pole">
|
|
<visual>
|
|
<geometry>
|
|
<cylinder length="0.2" radius=".01"/>
|
|
</geometry>
|
|
<origin rpy="0 1.57075 0 " xyz="0.1 0 0"/>
|
|
<material name="Gray">
|
|
<color rgba=".7 .7 .7 1"/>
|
|
</material>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<cylinder length="0.2" radius=".01"/>
|
|
</geometry>
|
|
<origin rpy="0 1.57075 0 " xyz="0.1 0 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.5"/>
|
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
<joint name="left_gripper_joint" type="revolute">
|
|
<axis xyz="0 0 1"/>
|
|
<limit effort="1000.0" lower="-2.0" upper="2.548" velocity="0.5"/>
|
|
<origin rpy="0 0 0" xyz="0.2 0.01 0"/>
|
|
<parent link="gripper_pole"/>
|
|
<child link="left_gripper"/>
|
|
</joint>
|
|
|
|
<link name="left_gripper">
|
|
<contact>
|
|
<lateral_friction value="1.0"/>
|
|
<spinning_friction value="1.5"/>
|
|
</contact>
|
|
<visual>
|
|
<origin rpy="0.0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="l_finger_collision.stl"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="0.0 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="l_finger_collision.stl"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.1"/>
|
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
<joint name="left_tip_joint" type="fixed">
|
|
<parent link="left_gripper"/>
|
|
<child link="left_tip"/>
|
|
</joint>
|
|
|
|
<link name="left_tip">
|
|
<contact>
|
|
<lateral_friction value="1.0"/>
|
|
<spinning_friction value="1.5"/>
|
|
</contact>
|
|
<visual>
|
|
<origin rpy="0.0 0 0" xyz="0.09137 0.00495 0"/>
|
|
<geometry>
|
|
<mesh filename="l_finger_tip.stl"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<box size=".03 .01 .02"/>
|
|
</geometry>
|
|
<origin rpy="0.0 0.0 0" xyz="0.105 -0.005 0"/>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.1"/>
|
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
<joint name="right_gripper_joint" type="revolute">
|
|
<axis xyz="0 0 -1"/>
|
|
<limit effort="1000.0" lower="-2.0" upper="2." velocity="0.5"/>
|
|
<origin rpy="0 0 0" xyz="0.2 -0.01 0"/>
|
|
<parent link="gripper_pole"/>
|
|
<child link="right_gripper"/>
|
|
</joint>
|
|
|
|
<link name="right_gripper">
|
|
<contact>
|
|
<lateral_friction value="1.0"/>
|
|
<spinning_friction value="1.5"/>
|
|
</contact>
|
|
<visual>
|
|
<origin rpy="-3.1415 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="l_finger_collision.stl"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<origin rpy="-3.1415 0 0" xyz="0 0 0"/>
|
|
<geometry>
|
|
<mesh filename="l_finger_collision.stl"/>
|
|
</geometry>
|
|
</collision>
|
|
<inertial>
|
|
<mass value="0.1"/>
|
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
|
</inertial>
|
|
</link>
|
|
|
|
<joint name="right_tip_joint" type="fixed">
|
|
<parent link="right_gripper"/>
|
|
<child link="right_tip"/>
|
|
</joint>
|
|
|
|
<link name="right_tip">
|
|
<contact>
|
|
<lateral_friction value="1.0"/>
|
|
<spinning_friction value="1.5"/>
|
|
</contact>
|
|
<visual>
|
|
<origin rpy="-3.1415 0 0" xyz="0.09137 0.00495 0"/>
|
|
<geometry>
|
|
<mesh filename="l_finger_tip.stl"/>
|
|
</geometry>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<box size=".03 .01 .02"/>
|
|
</geometry>
|
|
<origin rpy="-3.1415 0 0" xyz="0.105 0.015 0"/>
|
|
</collision>
|
|
<collision>
|
|
<geometry>
|
|
<box size=".01 .02 .02"/>
|
|
</geometry>
|
|
<origin rpy="-3.1415 0 -0.5" xyz="0.095 0.005 0"/>
|
|
</collision>
|
|
|
|
<inertial>
|
|
<mass value="0.1"/>
|
|
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
|
</inertial>
|
|
</link>
|
|
</robot>
|