pxmlw6n2f/sdformat_for_mpi/test/integration/model/turtlebot.sdf

475 lines
14 KiB
XML

<?xml version="1.0" ?>
<sdf version="1.4">
<model name="turtlebot">
<link name="rack">
<inertial>
<pose>0.001453 -0.000453 0.029787 0 0 0</pose>
<inertia>
<ixx>0.058640</ixx>
<ixy>0.000124</ixy>
<ixz>0.000615</ixz>
<iyy>0.058786</iyy>
<iyz>0.000014</iyz>
<izz>1.532440</izz>
</inertia>
<mass>2.234000</mass>
</inertial>
<collision name="plate_0_collision">
<pose>-0.043340 0 0.084757 0 0 0</pose>
<geometry>
<box>
<size>0.233502 0.314845 0.006401</size>
</box>
</geometry>
</collision>
<visual name="plate_0_visual">
<pose>-0.043340 0 0.084757 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/plate_0_logo.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="plate_1_collision">
<pose>-0.002660 0 0.141907 0 0 0</pose>
<geometry>
<box>
<size>0.314856 0.314856 0.006401</size>
</box>
</geometry>
</collision>
<visual name="plate_1_visual">
<pose>-0.002660 0 0.141907 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/plate_1_logo.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="plate_2_collision">
<pose>-0.002660 0 0.199108 0 0 0</pose>
<geometry>
<box>
<size>0.314856 0.314856 0.006401</size>
</box>
</geometry>
</collision>
<visual name="plate_2_visual">
<pose>-0.002660 0 0.199108 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/plate_1_logo.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="plate_3_collision">
<pose>-0.015820 0 0.405457 0 0 0</pose>
<geometry>
<box>
<size>0.288000 0.315000 0.006401</size>
</box>
</geometry>
</collision>
<visual name="plate_3_visual">
<pose>-0.015820 0 0.405457 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/plate_2_logo.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="spacer_0_collision">
<pose>-0.002540 0.111468 0.079992 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.012700</radius>
<length>0.003175</length>
</cylinder>
</geometry>
</collision>
<visual name="spacer_0_visual">
<pose>-0.002540 0.111468 0.079992 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-02403-125_Spacer.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="spacer_1_collision">
<pose>-0.002540 -0.111468 0.079992 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.012700</radius>
<length>0.003175</length>
</cylinder>
</geometry>
</collision>
<visual name="spacer_1_visual">
<pose>-0.002540 -0.111468 0.079992 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-02403-125_Spacer.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="spacer_2_collision">
<pose>-0.072390 -0.111468 0.079992 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.012700</radius>
<length>0.003175</length>
</cylinder>
</geometry>
</collision>
<visual name="spacer_2_visual">
<pose>-0.072390 -0.111468 0.079992 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-02403-125_Spacer.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="spacer_3_collision">
<pose>-0.072390 0.111468 0.079992 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.012700</radius>
<length>0.003175</length>
</cylinder>
</geometry>
</collision>
<visual name="spacer_3_visual">
<pose>-0.072390 0.111468 0.079992 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-02403-125_Spacer.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_2in_0_collision">
<pose>0.067640 0.131420 0.087980 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.038100</radius>
<length>0.063500</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_2in_0_visual">
<pose>0.067640 0.131420 0.087980 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_2in_1_collision">
<pose>0.067640 -0.131420 0.087980 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.038100</radius>
<length>0.063500</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_2in_1_visual">
<pose>0.067640 -0.131420 0.087980 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_2in_2_collision">
<pose>-0.052832 -0.131420 0.087980 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.038100</radius>
<length>0.063500</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_2in_2_visual">
<pose>-0.052832 -0.131420 0.087980 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_2in_3_collision">
<pose>-0.052832 0.131420 0.087980 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.038100</radius>
<length>0.063500</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_2in_3_visual">
<pose>-0.052832 0.131420 0.087980 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_2in_4_collision">
<pose>0.067640 0.131420 0.145130 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.038100</radius>
<length>0.063500</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_2in_4_visual">
<pose>0.067640 0.131420 0.145130 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_2in_5_collision">
<pose>0.067640 -0.131420 0.145130 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.038100</radius>
<length>0.063500</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_2in_5_visual">
<pose>0.067640 -0.131420 0.145130 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_2in_6_collision">
<pose>-0.052832 -0.131420 0.145130 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.038100</radius>
<length>0.063500</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_2in_6_visual">
<pose>-0.052832 -0.131420 0.145130 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_2in_7_collision">
<pose>-0.052832 0.131420 0.145130 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.038100</radius>
<length>0.063500</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_2in_7_visual">
<pose>-0.052832 0.131420 0.145130 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-04552-2000-RA_Turtlebot_M-F_Standoff.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_8in_0_collision">
<pose>0.067640 0.131420 0.202280 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.011113</radius>
<length>0.203200</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_8in_0_visual">
<pose>0.067640 0.131420 0.202280 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-02421-8000-RA_Turtlebot_F-F_Standoff.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_8in_1_collision">
<pose>0.067640 -0.131420 0.202280 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.011113</radius>
<length>0.203200</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_8in_1_visual">
<pose>0.067640 -0.131420 0.202280 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-02421-8000-RA_Turtlebot_F-F_Standoff.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_8in_2_collision">
<pose>-0.052832 -0.131420 0.202280 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.011113</radius>
<length>0.203200</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_8in_2_visual">
<pose>-0.052832 -0.131420 0.202280 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-02421-8000-RA_Turtlebot_F-F_Standoff.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_8in_3_collision">
<pose>-0.052832 0.131420 0.202280 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.011113</radius>
<length>0.203200</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_8in_3_visual">
<pose>-0.052832 0.131420 0.202280 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-02421-8000-RA_Turtlebot_F-F_Standoff.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_kinect_0_collision">
<pose>-0.105098 0.098000 0.202308 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.001111</radius>
<length>0.008585</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_kinect_0_visual">
<pose>-0.105098 0.098000 0.202308 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-04556-RA_Kinect_Standoff_Assy.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="standoff_kinect_1_collision">
<pose>-0.105098 -0.098000 0.202308 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.001111</radius>
<length>0.008585</length>
</cylinder>
</geometry>
</collision>
<visual name="standoff_kinect_1_visual">
<pose>-0.105098 -0.098000 0.202308 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot/meshes/68-04556-RA_Kinect_Standoff_Assy.dae</uri>
</mesh>
</geometry>
</visual>
<sensor name="laser" type="ray">
<pose>-0.065000 0 0.092000 0 0 0</pose>
<ray>
<scan>
<horizontal>
<samples>180</samples>
<resolution>1.000000</resolution>
<min_angle>-2.268928</min_angle>
<max_angle>2.268928</max_angle>
</horizontal>
</scan>
<range>
<min>0.080000</min>
<max>10</max>
<resolution>0.010000</resolution>
</range>
</ray>
<!--
<plugin name='laser_controller' filename='libgazebo_ros_laser.so'>
<gaussianNoise>0.005</gaussianNoise>
<alwaysOn>1</alwaysOn>
<updateRate>20</updateRate>
<topicName>scan</topicName>
<frameName>laser</frameName>
</plugin>-->
<update_rate>20</update_rate>
</sensor>
</link>
<include>
<uri>model://create</uri>
</include>
<include>
<uri>model://kinect</uri>
<pose>-0.087098 0 0.303857 0 0 0</pose>
</include>
<joint name='create_rack' type='revolute'>
<parent>create::base</parent>
<child>rack</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
</limit>
</axis>
</joint>
<joint name='kinect_rack' type='revolute'>
<parent>kinect::link</parent>
<child>rack</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>0</lower>
<upper>0</upper>
</limit>
</axis>
</joint>
</model>
</sdf>