Skip to content
Snippets Groups Projects
Unverified Commit 198a58d5 authored by Florent Lamiraux's avatar Florent Lamiraux Committed by GitHub
Browse files

Merge pull request #39 from florent-lamiraux/devel

[urdf] Import table from deprecated iai_maps package.
parents 1f9b2e64 d0dfbe2c
No related branches found
No related tags found
No related merge requests found
......@@ -52,6 +52,7 @@ install(FILES
urdf/kitchen_area.urdf
urdf/box_color.urdf
urdf/rod.urdf
urdf/table.urdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/urdf
)
install(FILES
......@@ -62,6 +63,7 @@ install(FILES
srdf/kitchen_area.srdf
srdf/rod.srdf
srdf/door.srdf
srdf/table.srdf
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/srdf
)
install(FILES
......
<robot name="table">
<contact name="pancake_table_table_top">
<link name="pancake_table_table_top_link"/>
<!-- Box size: size_x * size_y * size_z
x y z -->
<point>
0.8 0.3 0.0125
0.8 -0.3 0.0125
-0.8 0.3 0.0125
-0.8 -0.3 0.0125
</point>
<shape>
4 0 2 3 1
</shape>
</contact>
</robot>
<robot name="table">
<material name="KitchenWhite">
<color rgba="0.75 0.75 0.7 1.0"/>
</material>
<material name="KitchenLightGray">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<link name="base_link">
<inertial>
<mass value="2.0"/>
<inertia ixx="0.0601041666667" ixy="0" ixz="0" iyy="0.486666666667" iyz="0" izz="0.426770833333"/>
</inertial>
</link>
<joint name="pancake_table_table_joint" type="fixed">
<parent link="base_link"/>
<child link="pancake_table_table_link"/>
<origin rpy="0 0 1.57" xyz="0.8 0 0"/>
</joint>
<joint name="pancake_table_table_top_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.7175"/>
<parent link="pancake_table_table_link"/>
<child link="pancake_table_table_top_link"/>
</joint>
<link name="pancake_table_table_top_link">
<inertial>
<mass value="2.0"/>
<inertia ixx="0.0601041666667" ixy="0" ixz="0" iyy="0.486666666667" iyz="0" izz="0.426770833333"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="1.6 0.6 0.025"/>
</geometry>
<material name="KitchenWhite"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="1.6 0.6 0.025"/>
</geometry>
</collision>
</link>
<gazebo reference="pancake_table_table_top_link">
<kp>100000</kp>
<kd>1000000</kd>
<mu1>50000</mu1>
<mu2>50000</mu2>
<material value="KitchenWhite"/>
</gazebo>
<joint name="pancake_table_first_leg_joint" type="fixed">
<origin rpy="0 0 0 " xyz="-0.775 -0.275 0.350"/>
<parent link="pancake_table_table_link"/>
<child link="pancake_table_first_leg_link"/>
</joint>
<link name="pancake_table_first_leg_link">
<inertial>
<mass value="1.0"/>
<inertia ixx="0.0409895833333" ixy="0" ixz="0" iyy="0.0003125" iyz="0" izz="0.0409895833333"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.700" radius="0.025"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.700" radius="0.025"/>
</geometry>
</collision>
</link>
<gazebo reference="pancake_table_first_leg_link">
<material value="KitchenLightGray"/>
</gazebo>
<joint name="pancake_table_second_leg_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.775 -0.275 0.350"/>
<parent link="pancake_table_table_link"/>
<child link="pancake_table_second_leg_link"/>
</joint>
<link name="pancake_table_second_leg_link">
<inertial>
<mass value="1.0"/>
<inertia ixx="0.0409895833333" ixy="0" ixz="0" iyy="0.0003125" iyz="0" izz="0.0409895833333"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.700" radius="0.025"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.700" radius="0.025"/>
</geometry>
</collision>
</link>
<gazebo reference="pancake_table_second_leg_link">
<material value="KitchenLightGray"/>
</gazebo>
<joint name="pancake_table_third_leg_joint" type="fixed">
<origin rpy="0 0 0" xyz="-0.775 0.275 0.350"/>
<parent link="pancake_table_table_link"/>
<child link="pancake_table_third_leg_link"/>
</joint>
<link name="pancake_table_third_leg_link">
<inertial>
<mass value="1.0"/>
<inertia ixx="0.0409895833333" ixy="0" ixz="0" iyy="0.0003125" iyz="0" izz="0.0409895833333"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.700" radius="0.025"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.700" radius="0.025"/>
</geometry>
</collision>
</link>
<gazebo reference="pancake_table_third_leg_link">
<material value="KitchenLightGray"/>
</gazebo>
<joint name="pancake_table_fourth_leg_joint" type="fixed">
<origin rpy="0 0 0" xyz="0.775 0.275 0.350"/>
<parent link="pancake_table_table_link"/>
<child link="pancake_table_fourth_leg_link"/>
</joint>
<link name="pancake_table_fourth_leg_link">
<inertial>
<mass value="1.0"/>
<inertia ixx="0.0409895833333" ixy="0" ixz="0" iyy="0.0003125" iyz="0" izz="0.0409895833333"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.700" radius="0.025"/>
</geometry>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.700" radius="0.025"/>
</geometry>
</collision>
</link>
<gazebo reference="pancake_table_fourth_leg_link">
<material value="KitchenLightGray"/>
</gazebo>
<link name="pancake_table_table_link">
<inertial>
<mass value="0"/>
<inertia ixx="0.0" ixy="0" ixz="0" iyy="0.0" iyz="0" izz="0.0"/>
</inertial>
</link>
</robot>
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment