model
This commit is contained in:
parent
fc319d757e
commit
d75007d604
111
urdf/sample.urdf
111
urdf/sample.urdf
|
@ -1,152 +1,175 @@
|
||||||
<?xml version="1.0"?>
|
<?xml version="1.0"?>
|
||||||
<robot name="sample_robot">
|
<robot name="sample_robot">
|
||||||
<!-- links: main serial chain -->
|
|
||||||
|
<!-- Materials -->
|
||||||
|
<material name="grey">
|
||||||
|
<color rgba="0.0 0 0 1.0" />
|
||||||
|
</material>
|
||||||
|
<material name="red">
|
||||||
|
<color rgba="1.0 0.0 0.0 1.0" />
|
||||||
|
</material>
|
||||||
|
<material name="blue">
|
||||||
|
<color rgba="0 0.0 1.0 1.0" />
|
||||||
|
</material>
|
||||||
|
<material name="lightblue">
|
||||||
|
<color rgba="0.0 0.22 1.0 1.0" />
|
||||||
|
</material>
|
||||||
|
<material name="yellow">
|
||||||
|
<color rgba="0.96 0.76 0.13 1.0" />
|
||||||
|
</material>
|
||||||
|
<material name="orange">
|
||||||
|
<color rgba="1.0 0.5 0.0 1.0" />
|
||||||
|
</material>
|
||||||
|
<material name="black">
|
||||||
|
<color rgba="0.15 0.15 0.15 1.0" />
|
||||||
|
</material>
|
||||||
|
|
||||||
|
<!-- Links: main serial chain -->
|
||||||
<link name="base_link">
|
<link name="base_link">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="1.0" />
|
<mass value="1.0" />
|
||||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 -0.2" />
|
<origin rpy="0 0 0" xyz="0 0 0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.2 0.2 0.2" />
|
<mesh filename="../urdf_support/sample/1.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="grey">
|
<material name="grey"/>
|
||||||
<color rgba="0.0 0 0 1.0" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="link_1">
|
<link name="link_1">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="1.0" />
|
<mass value="1.0" />
|
||||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0.2473" />
|
<origin rpy="0 0 0" xyz="0 0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.1 0.1 0.4946" />
|
<mesh filename="../urdf_support/sample/2.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="red">
|
<material name="red"/>
|
||||||
<color rgba="1.0 0.0 0.0 1.0" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="link_2">
|
<link name="link_2">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="1.0" />
|
<mass value="1.0" />
|
||||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0.3649605" />
|
<origin rpy="0 0 0" xyz="0 0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.1 0.1 0.729921" />
|
<mesh filename="../urdf_support/sample/3.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="blue">
|
<material name="blue"/>
|
||||||
<color rgba="0 0.0 1.0 1.0" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="link_3">
|
<link name="link_3">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="1.0" />
|
<mass value="1.0" />
|
||||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0.049" />
|
<origin rpy="0 0 0" xyz="0 0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.1 0.1 0.098277" />
|
<mesh filename="../urdf_support/sample/4.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="lightblue">
|
<material name="lightblue"/>
|
||||||
<color rgba="0. 0.22 1.00 1.0" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="link_4">
|
<link name="link_4">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="1.0" />
|
<mass value="1.0" />
|
||||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0.5545195" />
|
<origin rpy="0 0 0" xyz="0 0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.1 0.1 1.109039" />
|
<mesh filename="../urdf_support/sample/5.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="yellow">
|
<material name="yellow"/>
|
||||||
<color rgba="0.96 0.76 0.13 1.0" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="link_5">
|
<link name="link_5">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="1.0" />
|
<mass value="1.0" />
|
||||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0.0585" />
|
<origin rpy="0 0 0" xyz="0 0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.1 0.1 0.117" />
|
<mesh filename="../urdf_support/sample/6.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="orange">
|
<material name="orange"/>
|
||||||
<color rgba="1.0 0.5 0.0 1.0" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
|
|
||||||
<link name="link_6">
|
<link name="link_6">
|
||||||
<inertial>
|
<inertial>
|
||||||
<mass value="1.0" />
|
<mass value="1.0" />
|
||||||
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
<inertia ixx="0.005" ixy="0.0" ixz="0.0" iyy="0.005" iyz="0.0" izz="0.005" />
|
||||||
</inertial>
|
</inertial>
|
||||||
<visual>
|
<visual>
|
||||||
<origin rpy="0 0 0" xyz="0 0 0.05" />
|
<origin rpy="0 0 0" xyz="0 0 0.0" />
|
||||||
<geometry>
|
<geometry>
|
||||||
<box size="0.1 0.1 0.1" />
|
<mesh filename="../urdf_support/sample/7.stl"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="black">
|
<material name="black"/>
|
||||||
<color rgba="0.15 0.15 0.15 1.0" />
|
|
||||||
</material>
|
|
||||||
</visual>
|
</visual>
|
||||||
</link>
|
</link>
|
||||||
<!-- joints: main serial chain -->
|
|
||||||
|
<!-- Joints: main serial chain -->
|
||||||
<joint name="joint_1" type="revolute">
|
<joint name="joint_1" type="revolute">
|
||||||
<limit effort="0" lower="-2.7925" upper="2.7925" velocity="3.1415" />
|
<limit effort="0" lower="-2.7925" upper="2.7925" velocity="3.1415" />
|
||||||
<origin rpy="0 0 0" xyz="0 0 0" />
|
<origin rpy="0 0 0" xyz="-0.011789 0.0278 0.26158" />
|
||||||
<parent link="base_link" />
|
<parent link="base_link" />
|
||||||
<child link="link_1" />
|
<child link="link_1" />
|
||||||
<axis xyz="0 0 1" />
|
<axis xyz="0 0 1" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="joint_2" type="revolute">
|
<joint name="joint_2" type="revolute">
|
||||||
<limit effort="0" lower="-0.5759" upper="2.6529" velocity="3.1415" />
|
<limit effort="0" lower="-0.5759" upper="2.6529" velocity="3.1415" />
|
||||||
<parent link="link_1" />
|
<parent link="link_1" />
|
||||||
<child link="link_2" />
|
<child link="link_2" />
|
||||||
<axis xyz="0 -1 0" />
|
<axis xyz="0 -1 0" />
|
||||||
<origin rpy="0 0 0" xyz="0.0170450 0 0.494600" />
|
<origin rpy="0 0 0" xyz="-0.168621 0.103 0.23445" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="joint_3" type="revolute">
|
<joint name="joint_3" type="revolute">
|
||||||
<origin rpy="0 1.5708 0" xyz="0 0 0.729921" />
|
<limit effort="0" lower="-2.6145" upper="2.8797" velocity="3.9269" />
|
||||||
<parent link="link_2" />
|
<parent link="link_2" />
|
||||||
<child link="link_3" />
|
<child link="link_3" />
|
||||||
<axis xyz="0 -1 0" />
|
<axis xyz="0 -1 0" />
|
||||||
<limit effort="0" lower="-2.6145" upper="2.8797" velocity="3.9269" />
|
<origin rpy="0 0 0" xyz="0.35988 -0.00232 0.63457" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="joint_4" type="revolute">
|
<joint name="joint_4" type="revolute">
|
||||||
<limit effort="0" lower="-3.3161" upper="3.3161" velocity="6.9813" />
|
<limit effort="0" lower="-3.3161" upper="3.3161" velocity="6.9813" />
|
||||||
<parent link="link_3" />
|
<parent link="link_3" />
|
||||||
<child link="link_4" />
|
<child link="link_4" />
|
||||||
<axis xyz="0 0 1" />
|
<axis xyz="0 0 1" />
|
||||||
<origin rpy="0 0 0" xyz="0 0 0.098277" />
|
<origin rpy="0 0 0" xyz="-0.23985 -0.101766 0.0983" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="joint_5" type="revolute">
|
<joint name="joint_5" type="revolute">
|
||||||
<limit effort="0" lower="-2.0943" upper="2.0943" velocity="5.7595" />
|
<limit effort="0" lower="-2.0943" upper="2.0943" velocity="5.7595" />
|
||||||
<parent link="link_4" />
|
<parent link="link_4" />
|
||||||
<child link="link_5" />
|
<child link="link_5" />
|
||||||
<axis xyz="0 1 0" />
|
<axis xyz="0 1 0" />
|
||||||
<origin rpy="0 0 0" xyz="0.0 0 1.109039" />
|
<origin rpy="0 0 0" xyz="-0.867755 -0.037912 0.0021" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
<joint name="joint_6" type="revolute">
|
<joint name="joint_6" type="revolute">
|
||||||
<limit effort="0" lower="-6.2831" upper="6.2831" velocity="8.3775" />
|
<limit effort="0" lower="-6.2831" upper="6.2831" velocity="8.3775" />
|
||||||
<parent link="link_5" />
|
<parent link="link_5" />
|
||||||
<child link="link_6" />
|
<child link="link_6" />
|
||||||
<axis xyz="0 0 1" />
|
<axis xyz="0 0 1" />
|
||||||
<origin rpy="0 0 0" xyz="0.0 0 0.117" />
|
<origin rpy="0 0 0" xyz="-0.12086 0.039025 0.0002" />
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Loading…
Reference in New Issue