环境:ubuntu16.04 ros-kinetic gazebo7.16
问题来源:仿真时候,激光雷达传感器数据过于完美了,有点不符合实际应用.那么,知道如何定义模拟传感器的噪音大小很有必须.当然,仿真里面在urdf里面定义的参数含义理解也是很重要的.
注意:使用时,代码里面的中文描述都是去掉的,否则会触发一些奇怪错误
解决方法:
下面截取urdf里面对应一个激光传感器作为案例展示:
<gazebo reference="scanner_link">
<sensor type="ray" name="hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>30</update_rate>//雷达数据更新频率
<ray>
<!--define the line parameter of senser laser-->
<scan>
<horizontal>//水平方向参数
<samples>640</samples>//射线条数
<resolution>1</resolution>//分辨率
<min_angle>-2</min_angle>
<max_angle>2</max_angle>//这两定义是传感器角度范围
</horizontal>
</scan>
<range>//定义雷达射程范围以及分辨率
<min>0.05</min>
<max>10.0</max>
<resolution>0.01</resolution>
</range>
<!--define noise-->
<noise>//定义传感器噪声
<type>gaussian</type>//噪声类型
<!-- Noise parameters based on published spec for Hokuyo laser
achieving "+-30mm" accuracy at range < 10m. A mean of 0.0m and
stddev of 0.01m will put 99.7% of samples within 0.03m of the true
reading. -->
<mean>0</mean>//平均值
<stddev>0.01</stddev>//标准差好像,这个有点忘了
</noise>
</ray>
<!--define the topic of the senser laser1 between the gazebo and ros in simulation information exchange.-->
<plugin name="gazebo_ros_hokuyo_controller" filename="libgazebo_ros_laser.so">//应用的激光传感器插件类型
<topicName>scanner</topicName>//雷达发到ros里面的topic名称
<frameName>scanner_link</frameName>//传感器发出的数据依靠的link,这个会在相机仿真里面有重要应用
</plugin>
</sensor>
</gazebo>
对于仿真时候用到的激光雷达,在urdf里面定义基本样式也就是这样子了,理解里面每一句话的含义,基本上仿真雷达定义也就ok了.
20191111
##################
好记性不如烂笔头
–20200723