bullet3/data/hinge.urdf
erwincoumans 17219f84c6 make setJointPosMultiDof and setJointVelMultiDof argument const.
add PyBullet.resetJointStateMultiDof / getJointStateMultiDof, for preliminary support for spherical and planar joints
2018-11-10 14:26:31 -08:00

75 lines
1.9 KiB
XML

<?xml version="1.0" ?>
<robot name="urdf_robot">
<link name="baseLink">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0.35"/>
<mass value="0.0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0.35"/>
<geometry>
<box size="0.08 0.16 0.7"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.35"/>
<geometry>
<box size="0.08 0.16 0.7"/>
</geometry>
</collision>
</link>
<link name="childA">
<inertial>
<origin rpy="0 0 0" xyz="0 0 -0.36"/>
<mass value="1.0"/>
<inertia ixx="0.048966669" ixy="0" ixz="0" iyy="0.046466667" iyz="0" izz="0.0041666669"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 -0.36"/>
<geometry>
<box size="0.1 0.2 0.72"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.36"/>
<geometry>
<box size="0.1 0.2 0.72 "/>
</geometry>
</collision>
</link>
<joint name="joint_baseLink_childA" type="spherical">
<parent link="baseLink"/>
<child link="childA"/>
<origin xyz="0 0 0"/>
<axis xyz="1 0 0"/>
</joint>
<link name="childB">
<inertial>
<origin rpy="0 0 0" xyz="0 0 -0.36"/>
<mass value="1.0"/>
<inertia ixx="0.048966669" ixy="0" ixz="0" iyy="0.046466667" iyz="0" izz="0.0041666669"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 -0.36"/>
<geometry>
<box size="0.1 0.2 0.3 "/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -0.36"/>
<geometry>
<box size="0.1 0.2 0.3 "/>
</geometry>
</collision>
</link>
<joint name="joint_childA_childB" type="continuous">
<parent link="childA"/>
<child link="childB"/>
<origin xyz="0 0 -0.2"/>
<axis xyz="1 0 0"/>
</joint>
</robot>