mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-04 17:40:06 +00:00
Add pole urdf.
This commit is contained in:
parent
dda1b05f4a
commit
39bdd00ce5
140
data/pole.urdf
Executable file
140
data/pole.urdf
Executable file
@ -0,0 +1,140 @@
|
||||
<?xml version="1.0"?>
|
||||
<robot name="physics">
|
||||
|
||||
<link name="slideBar">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="30 0.05 0.05"/>
|
||||
</geometry>
|
||||
<origin xyz="0 0 0"/>
|
||||
<material name="green">
|
||||
<color rgba="0 0.8 .8 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<inertial>
|
||||
<mass value="0"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
|
||||
<link name="pole">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.05 0.05 1.0"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0"/>
|
||||
<mass value="10"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.05 0.05 1.0"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="cart_to_pole" type="prismatic">
|
||||
<axis xyz="1 0 0"/>
|
||||
<origin xyz="0.0 0.0 0.5"/>
|
||||
<parent link="slideBar"/>
|
||||
<child link="pole"/>
|
||||
<limit effort="1000.0" lower="-5" upper="5" velocity="0.5"/>
|
||||
</joint>
|
||||
|
||||
<link name="pole2">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.05 0.05 1.0"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.5"/>
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.5"/>
|
||||
<mass value="10"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.05 0.05 1.0"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.5"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="pole_to_pole2" type="continuous">
|
||||
<axis xyz="1 0 0"/>
|
||||
<origin xyz="0.0 0.0 0.5"/>
|
||||
<parent link="pole"/>
|
||||
<child link="pole2"/>
|
||||
</joint>
|
||||
|
||||
<link name="pole3">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.05 0.05 1.0"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.5"/>
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0.5"/>
|
||||
<mass value="10"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.05 0.05 1.0"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.5"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="pole2_to_pole3" type="continuous">
|
||||
<axis xyz="0 1 0"/>
|
||||
<origin xyz="0.0 0.0 1"/>
|
||||
<parent link="pole2"/>
|
||||
<child link="pole3"/>
|
||||
</joint>
|
||||
|
||||
<link name="endeffector">
|
||||
<visual>
|
||||
<geometry>
|
||||
<box size="0.06 0.06 .06"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="red">
|
||||
<color rgba="1 0 0 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0"/>
|
||||
<mass value="10"/>
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
<collision>
|
||||
<geometry>
|
||||
<box size="0.06 0.06 .06"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
</link>
|
||||
|
||||
<joint name="pole2_to_endeffector" type="fixed">
|
||||
<origin xyz="0.0 0.0 1"/>
|
||||
<parent link="pole3"/>
|
||||
<child link="endeffector"/>
|
||||
</joint>
|
||||
|
||||
</robot>
|
Loading…
Reference in New Issue
Block a user