XTDrone/sitl_config/models/hokuyo_lidar/model.sdf

80 lines
2.3 KiB
XML

<?xml version="1.0" ?>
<sdf version="1.5">
<model name="hokuyo_lidar">
<pose>0 0 0 0 0 0</pose>
<link name="link">
<inertial>
<mass>0.001</mass>
<inertia> <!-- inertias are tricky to compute -->
<ixx>0.001</ixx>
<!-- for a box: ixx = 0.083 * mass * (y*y + z*z) -->
<ixy>0.0</ixy>
<!-- for a box: ixy = 0 -->
<ixz>0.0</ixz>
<!-- for a box: ixz = 0 -->
<iyy>0.001</iyy>
<!-- for a box: iyy = 0.083 * mass * (x*x + z*z) -->
<iyz>0.0</iyz>
<!-- for a box: iyz = 0 -->
<izz>0.001</izz>
<!-- for a box: izz = 0.083 * mass * (x*x + y*y) -->
</inertia>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>model://hokuyo_lidar/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<collision name="collision-base">
<pose>0 0 -0.0145 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.041</size>
</box>
</geometry>
</collision>
<collision name="collision-top">
<pose>0 0 0.0205 0 0 0</pose>
<geometry>
<cylinder>
<radius>0.021</radius>
<length>0.029</length>
</cylinder>
</geometry>
</collision>
<sensor name="laser" type="ray">
<pose>0 0 0.0175 0 -0 0</pose>
<ray>
<scan>
<horizontal>
<samples>512</samples>
<resolution>1</resolution>
<min_angle>-2.09</min_angle>
<max_angle>2.09</max_angle>
</horizontal>
</scan>
<range>
<min>0.45</min>
<max>5</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<robotNamespace></robotNamespace>
<topicName>scan</topicName>
<frameName>laser_2d</frameName>
</plugin>
<always_on>1</always_on>
<update_rate>500</update_rate>
<visualize>True</visualize>
</sensor>
</link>
</model>
</sdf>