为一些物体设置一个高值可以使模拟的2D激光雷达扫描仪输出包含反射器存在的角度的高强度数据成为可能。这行得通吗?
我想在gazebo中模拟激光雷达并进行rosbag的录制,但是网上的教程基本都是对range进行设置和记录,而无法收取物体的反射强度,这里给出如何设置物体的光反射强度。所用环境为ubuntu 18.04, ros melodic
- gazebo 9.0 无法获得强度模拟,需要更新到11 ,链接为https://blog.csdn.net/weixin_44623637/article/details/109249607
- 激光雷达配置文件laser.xacro为
<robot name="my_sensors" xmlns:xacro="http://wiki.ros.org/xacro">
<gazebo reference="laser">
<sensor type="ray" name="head_hokuyo_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>1000</samples>
<resolution>1</resolution>
<min_angle>-3</min_angle>
<max_angle>3</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>30.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_head_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/scan</topicName>
<frameName>laser</frameName> <!-- change here check demo07-car-laser's link name-->
</plugin>
</sensor>
</gazebo>
</robot>
- 重点是世界中物体反射强度的设置
(1)我建立的环境如下
选中物体在左侧栏中可看到属性laser_retro的值,默认为0
(2)设置环境中的物体的反射强度值,以环境中的圆柱(用作反光板)为例,gazebo中选中物体,查看名称,到对应的.world文件(由gazebo建立环境后存储)下找到对应描述。当然需要首先edit model来建立一个形状,这里我讲这个model命名为reflector,其实就是圆柱修改了半径和高度尺寸。
上图中反光板名称为link_clone_clone,因此在.world描述文件中可找到相关段落:
<model name='reflector'>
<link name='link_clone_clone'>
<inertial>
<mass>1</mass>
<inertia>
<ixx>0.145833</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.145833</iyy>
<iyz>0</iyz>
<izz>0.125</izz>
</inertia>
<pose>0 0 0 0 -0 0</pose>
</inertial>
<self_collide>0</self_collide>
<enable_wind>0</enable_wind>
<kinematic>0</kinematic>
<pose>-3.29191 0.432873 -0 0 -0 0</pose>
<gravity>1</gravity>
<visual name='visual'>
<laser_retro>255.0</laser_retro> // 添加语句
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.5</length>
</cylinder>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
<uri>file://media/materials/scripts/gazebo.material</uri>
</script>
<shader type='pixel'>
<normal_map>__default__</normal_map>
</shader>
<ambient>0.3 0.3 0.3 1</ambient>
<diffuse>0.7 0.7 0.7 1</diffuse>
<specular>0.01 0.01 0.01 1</specular>
<emissive>0 0 0 1</emissive>
</material>
<pose>0 0 0 0 -0 0</pose>
<transparency>0</transparency>
<cast_shadows>1</cast_shadows>
</visual>
<collision name='collision'>
<laser_retro>255.0</laser_retro> // 添加语句
<max_contacts>10</max_contacts>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.5</length>
</cylinder>
</geometry>
<surface>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
<fdir1>0 0 0</fdir1>
<slip1>0</slip1>
<slip2>0</slip2>
</ode>
<torsional>
<coefficient>1</coefficient>
<patch_radius>0</patch_radius>
<surface_radius>0</surface_radius>
<use_patch_radius>1</use_patch_radius>
<ode>
<slip>0</slip>
</ode>
</torsional>
</friction>
<bounce>
<restitution_coefficient>0</restitution_coefficient>
<threshold>1e+06</threshold>
</bounce>
<contact>
<collide_without_contact>0</collide_without_contact>
<collide_without_contact_bitmask>1</collide_without_contact_bitmask>
<collide_bitmask>1</collide_bitmask>
<ode>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+13</kp>
<kd>1</kd>
<max_vel>0.01</max_vel>
<min_depth>0</min_depth>
</ode>
<bullet>
<split_impulse>1</split_impulse>
<split_impulse_penetration_threshold>-0.01</split_impulse_penetration_threshold>
<soft_cfm>0</soft_cfm>
<soft_erp>0.2</soft_erp>
<kp>1e+13</kp>
<kd>1</kd>
</bullet>
</contact>
</surface>
</collision>
</link>
在上述部分添加相关语句,格式为<laser_retro>255.0</laser_retro>。
然后即可rostopic echo /scan 看到收到的range和强度数据。