XTDrone/sitl_config/models/3d_lidar/3d_lidar.sdf

62 lines
1.5 KiB
XML

<?xml version="1.0"?>
<sdf version="1.5">
<model name="3d_lidar">
<link name="link">
<inertial>
<pose>0 0 0 0 0 0</pose>
<mass>0.001</mass>
<inertia>
<ixx>4.15e-6</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2.407e-6</iyy>
<iyz>0</iyz>
<izz>2.407e-6</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<mesh>
<uri>model://hokuyo/meshes/hokuyo.dae</uri>
</mesh>
</geometry>
</visual>
<sensor name='3d_lidar' type='ray'>
<ray>
<scan>
<horizontal>
<samples>512</samples>
<resolution>1</resolution>
<min_angle>-3.1415926535897931</min_angle>
<max_angle>3.1415926535897931</max_angle>
</horizontal>
<vertical>
<samples>32</samples>
<min_angle>-0.2617993877991494365</min_angle>
<max_angle>0.2617993877991494365</max_angle>
</vertical>
</scan>
<range>
<min>0.2</min>
<max>30</max>
<resolution>0.01</resolution>
</range>
</ray>
<plugin name='3d_laser' filename='libgazebo_ros_velodyne_laser.so'>
<topicName>/velodyne_points</topicName>
<frameName>laser_3d</frameName>
<gaussianNoise>0.008</gaussianNoise>
</plugin>
<always_on>1</always_on>
<update_rate>15</update_rate>
<visualize>0</visualize>
</sensor>
</link>
</model>
</sdf>