EAI激光雷达X4使用gmapping与laser_scan_matcher建图(二)
以下便是gmapping+laser_scan_matcher提供的2Dpose的launch文件源码,这里将laser_scan_matcher提供的2Dpose当作里程计来使用:
<!-- Example launch file: uses laser_scan_matcher together with slam_gmapping -->
<launch>
##################### set up data playback from bag ####################
<param name="/use_sim_time" value="false"/>
############################ EAI X4 laser ##############################
<include file="$(find ydlidar)/launch/x4.launch" />
################################ IMU ###################################
<include file="$(find razor_imu_9dof)/launch/razor-pub-and-display.launch" />
########################## IMU and odom EKF ############################
<!--include file="$(find robot_pose_ekf)/test/test_robot_pose_ekf.launch" /-->
######## publish an example base_link -> base_imu_link transform #######
<!--node pkg="tf" type="static_transform_publisher" name="base_imu_link"
args="0 0 0 0 3.1415926 0 /base_link /base_imu_link 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 = "map"/-->
<param name="fixed_frame" value = "odom"/>
<param name="base_frame" value = "base_link"/>
<param name="use_imu" value = "true"/>
<param name="max_iterations" value="10"/>
</node>
########################### start gmapping #############################
<node pkg="gmapping" type="slam_gmapping" name="slam_gmapping" output="screen">
<param name="scan_topic" value="scan" />
<param name="base_frame" value="base_link"/>
<param name="odom_frame" value="odom"/>
<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>
建图效果如下: