sensor_sim/description/lidar.xacro

72 lines
2.2 KiB
XML

<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" >
<xacro:include filename="inertial_macros.xacro"/>
<joint name="laser_joint" type="fixed">
<parent link="chassis"/>
<child link="laser_frame"/>
<origin xyz="-0.994175 0.0 1.0387512" rpy="0 ${9.0*deg_to_rad} 0"/>
</joint>
<link name="laser_frame">
<visual>
<geometry>
<box size="0.105 0.1316 0.065"/>
</geometry>
<material name="red"/>
</visual>
<collision>
<geometry>
<box size="0.105 0.1316 0.065"/>
</geometry>
</collision>
<xacro:inertial_cylinder mass="0.1" length="0.04" radius="0.05">
<origin xyz="0 0 0" rpy="0 0 0"/>
</xacro:inertial_cylinder>
</link>
<gazebo reference="laser_frame">
<material>Gazebo/Red</material>
<sensor name='gpu_lidar' type='gpu_lidar'>
<topic>lidar</topic>
<update_rate>5</update_rate>
<ignition_frame_id>laser_frame</ignition_frame_id>
<ray>
<scan>
<horizontal>
<samples>666</samples>
<resolution>1</resolution>
<min_angle>${-60*deg_to_rad}</min_angle>
<max_angle>${60*deg_to_rad}</max_angle>
</horizontal>
<vertical>
<samples>108</samples>
<resolution>1</resolution>
<min_angle>${-12.5*deg_to_rad}</min_angle>
<max_angle>${12.5*deg_to_rad}</max_angle>
</vertical>
</scan>
<range>
<min>0.08</min>
<max>60.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<alwaysOn>true</alwaysOn>
</sensor>
<visual>
<plugin filename="ignition-gazebo-label-system" name="ignition::gazebo::systems::Label">
<label>30</label>
</plugin>
</visual>
</gazebo>
</robot>