67 lines
2.0 KiB
XML
67 lines
2.0 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="-1.1 0.0 1.0" rpy="0 0 0"/>
|
|
</joint>
|
|
|
|
|
|
<link name="laser_frame">
|
|
<visual>
|
|
<geometry>
|
|
<cylinder radius="0.05" length="0.04"/>
|
|
</geometry>
|
|
<material name="red"/>
|
|
</visual>
|
|
<collision>
|
|
<geometry>
|
|
<cylinder radius="0.05" length="0.04"/>
|
|
</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>640</samples>
|
|
<resolution>1</resolution>
|
|
<min_angle>${-90*deg_to_rad}</min_angle>
|
|
<max_angle>${90*deg_to_rad}</max_angle>
|
|
</horizontal>
|
|
<vertical>
|
|
<samples>64</samples>
|
|
<resolution>1</resolution>
|
|
<min_angle>${-45*deg_to_rad}</min_angle>
|
|
<max_angle>${0*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>
|
|
</gazebo>
|
|
</robot> |