turtlebot3_simulations/turtlebot3_gazebo/models/turtlebot3_burger/model-1_4.sdf
2018-03-15 17:34:54 +09:00

248 lines
6.2 KiB
XML

<?xml version="1.0" ?>
<sdf version="1.4">
<model name="turtlebot3_burger">
<link name="base">
<inertial>
<pose>-0.032 0 0.070 0 0 0</pose>
<inertia>
<ixx>0.001</ixx>
<ixy>0.000</ixy>
<ixz>0.000</ixz>
<iyy>0.001</iyy>
<iyz>0.000</iyz>
<izz>0.001</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="base_collision">
<pose>-0.032 0 0.070 0 0 0</pose>
<geometry>
<box>
<size>0.140 0.140 0.140</size>
</box>
</geometry>
</collision>
<visual name="base_visual">
<pose>-0.032 0 0 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot3_burger/meshes/burger_base.dae</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
</visual>
<collision name="caster_collision">
<pose>-0.081 0 -0.004 0 0 0</pose>
<geometry>
<sphere>
<radius>0.005000</radius>
</sphere>
</geometry>
<surface>
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
</friction>
</surface>
</collision>
</link>
<link name="lidar">
<inertial>
<pose>-0.020 0 0.161 0 0 0</pose>
<inertia>
<ixx>0.001</ixx>
<ixy>0.000</ixy>
<ixz>0.000</ixz>
<iyy>0.001</iyy>
<iyz>0.000</iyz>
<izz>0.001</izz>
</inertia>
<mass>0.125</mass>
</inertial>
<collision name="lidar_sensor_collision">
<pose>-0.020 0 0.161 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.0508</radius>
<length>0.055</length>
</cylinder>
</geometry>
</collision>
<visual name="lidar_sensor_visual">
<pose>-0.032 0 0.171 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot3_burger/meshes/lds.dae</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
</visual>
<sensor name="hls_lfcd_lds" type="ray">
<always_on>1</always_on>
<visualize>0</visualize>
<pose>-0.032 0 0.171 0 0 0</pose>
<update_rate>1800</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1.000000</resolution>
<min_angle>0.000000</min_angle>
<max_angle>6.280000</max_angle>
</horizontal>
</scan>
<range>
<min>0.120000</min>
<max>3.5</max>
<resolution>0.015000</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
</sensor>
</link>
<link name="left_wheel">
<inertial>
<pose>0 0.08 0.023 -1.57 0 0</pose>
<inertia>
<ixx>0.001</ixx>
<ixy>0.000</ixy>
<ixz>0.000</ixz>
<iyy>0.001</iyy>
<iyz>0.000</iyz>
<izz>0.001</izz>
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="left_wheel_collision">
<pose>0 0.08 0.023 -1.57 0 0</pose>
<geometry>
<cylinder>
<radius>0.033</radius>
<length>0.018</length>
</cylinder>
</geometry>
<surface>
<!-- This friction pamareter don't contain reliable data!! -->
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="left_wheel_visual">
<pose>0 0.08 0.023 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot3_burger/meshes/left_tire.dae</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
</visual>
</link>
<link name="right_wheel">
<inertial>
<pose>0.0 -0.08 0.023 -1.57 0 0</pose>
<inertia>
<ixx>0.001</ixx>
<ixy>0.000</ixy>
<ixz>0.000</ixz>
<iyy>0.001</iyy>
<iyz>0.000</iyz>
<izz>0.001</izz>
</inertia>
<mass>0.1</mass>
</inertial>
<collision name="right_wheel_collision">
<pose>0.0 -0.08 0.023 -1.57 0 0</pose>
<geometry>
<cylinder>
<radius>0.033</radius>
<length>0.018</length>
</cylinder>
</geometry>
<surface>
<!-- This friction pamareter don't contain reliable data!! -->
<friction>
<ode>
<mu>100000.0</mu>
<mu2>100000.0</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0.0</slip1>
<slip2>0.0</slip2>
</ode>
</friction>
</surface>
</collision>
<visual name="right_wheel_visual">
<pose>0.0 -0.08 0.023 0 0 0</pose>
<geometry>
<mesh>
<uri>model://turtlebot3_burger/meshes/right_tire.dae</uri>
<scale>0.001 0.001 0.001</scale>
</mesh>
</geometry>
</visual>
</link>
<joint name="left_wheel_joint" type="revolute">
<parent>base</parent>
<child>left_wheel</child>
<pose>0.0 0.08 0.023 -1.57 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint name="right_wheel_joint" type="revolute">
<parent>base</parent>
<child>right_wheel</child>
<pose>0.0 -0.08 0.023 -1.57 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
</axis>
</joint>
<joint name="lidar_joint" type="fixed">
<parent>base</parent>
<child>lidar</child>
<pose>-0.032 0 0.171 0 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
<use_parent_model_frame>true</use_parent_model_frame>
</axis>
</joint>
</model>
</sdf>