ROS使用gmapping建图,需要激光雷达和里程计,在只有激光雷达的时候,可以使用Laser scan tools for ROS通过激光雷达连续扫描数据推算出里程数据,实现无里程计的激光雷达建图
确保功能包已安装
$ sudo apt-get install ros-melodic-gmapping
安装laser_scan_tools
$ git clone https://github.com/ccny-ros-pkg/scan_tools.git
将laser_scan_matcher功能包文件夹移至ROS项目空间文件夹 /src,并且将雷达功能包也放到同位置,然后进行编译
$ cd ydlidar_ws/src #进入存放的项目空间文件夹
$ catkin_make
进入src/laser_scan_matcher/demo,修改demo_gmapping.launch如下
<!--
Example launch file: uses laser_scan_matcher together with
slam_gmapping
-->
<launch>
#### set up data playback from bag #############################
<param name="/use_sim_time" value="flase"/><!-- 因为Gmapping 的simulation 时间是True, 改为false 网上查到的 -->
#### rplidar_X2L ################################################
<!--激光雷达的启动文件-->
<node name="ydlidar_lidar_publisher" pkg="ydlidar_ros_driver" type="ydlidar_ros_driver_node" output="screen" respawn="false" >
<!-- string property -->
<param name="port" type="string" value="/dev/ydlidar"/>
<param name="frame_id" type="string" value="laser"/>
<param name="ignore_array" type="string" value=""/>
<!-- int property -->
<param name="baudrate" type="int" value="115200"/>
<!-- 0:TYPE_TOF, 1:TYPE_TRIANGLE, 2:TYPE_TOF_NET -->
<param name="lidar_type" type="int" value="1"/>
<!-- 0:YDLIDAR_TYPE_SERIAL, 1:YDLIDAR_TYPE_TCP -->
<param name="device_type" type="int" value="0"/>
<param name="sample_rate" type="int" value="3"/>
<param name="abnormal_check_count" type="int" value="4"/>
<!-- bool property -->
<param name="resolution_fixed" type="bool" value="true"/>
<param name="auto_reconnect" type="bool" value="true"/>
<param name="reversion" type="bool" value="false"/>
<param name="inverted" type="bool" value="true"/>
<param name="isSingleChannel" type="bool" value="true"/>
<param name="intensity" type="bool" value="false"/>
<param name="support_motor_dtr" type="bool" value="true"/>
<param name="invalid_range_is_inf" type="bool" value="false"/>
<param name="point_cloud_preservative" type="bool" value="false"/>
<!-- float property -->
<param name="angle_min" type="double" value="-180" />
<param name="angle_max" type="double" value="180" />
<param name="range_min" type="double" value="0.1" />
<param name="range_max" type="double" value="12.0" />
<!-- frequency is invalid, External PWM control speed -->
<param name="frequency" type="double" value="10.0"/>
</node>
#### publish an example base_link -> laser transform ###########
<node pkg="tf" type="static_transform_publisher" name="base_link_to_laser"
args="0.0 0.0 0.0 0.0 0.0 0.0 /base_link /laser 40" />
#### start rviz ################################################
<node pkg="rviz" type="rviz" name="rviz"
args="-d $(find laser_scan_matcher)/demo/demo_gmapping.rviz"/>
#### start the laser scan_matcher ##############################
<node pkg="laser_scan_matcher" type="laser_scan_matcher_node"
name="laser_scan_matcher_node" output="screen">
<param name="fixed_frame" value = "odom"/>
<param name="max_iterations" value="10"/>
<param name="base_frame" value = "base_link"/>
<param name="use_odom" value="false"/>
<param name="publy_pose" value = "true"/>
<param name="publy_tf" value="true"/>
</node>
#### start gmapping ############################################
<!--前三个param必须设置修改,要不然tf_tree不完整-->
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<param name="base_frame" value="/base_link"/> <!--***机器人的坐标系-->
<param name="odom_frame" value="/odom" /> <!--***世界坐标系-->
<param name="map_frame" value="/map" /> <!--***地图坐标系-->
<param name="map_udpate_interval" value="1.0"/>
<param name="maxUrange" value="5.0"/>
<param name="sigma" value="0.1"/>
<param name="kernelSize" value="1"/>
<param name="lstep" value="0.15"/>
<param name="astep" value="0.15"/>
<param name="iterations" value="1"/>
<param name="lsigma" value="0.1"/>
<param name="ogain" value="3.0"/>
<param name="lskip" value="1"/>
<param name="srr" value="0.1"/>
<param name="srt" value="0.2"/>
<param name="str" value="0.1"/>
<param name="stt" value="0.2"/>
<param name="linearUpdate" value="1.0"/>
<param name="angularUpdate" value="0.5"/>
<param name="temporalUpdate" value="0.4"/>
<param name="resampleThreshold" value="0.5"/>
<param name="particles" value="10"/>
<param name="xmin" value="-5.0"/>
<param name="ymin" value="-5.0"/>
<param name="xmax" value="5.0"/>
<param name="ymax" value="5.0"/>
<param name="delta" value="0.02"/>
<param name="llsamplerange" value="0.01"/>
<param name="llsamplestep" value="0.05"/>
<param name="lasamplerange" value="0.05"/>
<param name="lasamplestep" value="0.05"/>
</node>
</launch>
如果是其他型号的雷达,可以根据雷达驱动文档,在上述<node name=”ydlidar_lidar_publisher”…>节点找到对应参数进行修改。
在项目空间目录下,启动gmapping demo
roslaunch laser_scan_matcher demo_gmapping.launch
rviz成功显示扫描出来的空间后,如果需要保存地图,安装map_server功能包
$ sudo apt-get install ros-melodic-map-server
在rviz显示扫描的图像差不多后,另外打开一个控制台
$ rosrun map_server map_saver -f ydlidar_ws/map
其中ydlidar_ws/map,ydlidar_ws为文件路径,map为文件名,最终可以在文件夹中找到map.pgm和map.yaml两个地图文件
发表回复