ROS与SLAM入门教程-激光雷达(EAI F4)hector_slam构建地图
ROS与SLAM入门教程-激光雷达(EAI F4)hector_slam构建地图
说明
- 介绍Turtlebot搭载激光雷达(EAI F4)通过hector_slam构建地图
准备
- 测试环境ubuntu14.04 + indigo
- 已安装Turtlebot包,具体安装:deb包安装 | 源码安装
- 依赖包:
- Turtlebot应用包,https://github.com/ncnynl/turtlebot_apps.git
- 激光雷达驱动,https://github.com/EAIBOT/flashgo.git
步骤
- 详细F4雷达安装参考:ROS与激光雷达入门教程-ROS中使用激光雷达(EAI F4)
- 建立工作空间(也可以利用现有的),编译包
$ mkdir -p ~/turtlebot_ws/src
$ cd ~/turtlebot_ws/src
## turtlebot建图依赖包
$ git clone https://github.com/turtlebot/turtlebot_apps
## hector_slam包,indigo桌面版已包含,如没,如下方式安装
$sudo apt-get install ros-indigo-hector-slam
#编译
$ cd ~/turtlebot_ws
$ catkin_make
- 添加环境变量,在~/.bashrc最后添加一行:
$ source /home/ubu/turtlebot_ws/devel/setup.bash
- 刷新配置
$ source ~/.bashrc
- 或
$ rospack profile
制作雷达驱动启动文件
- 复制lidar.launch到flashlidar-laser.launch,并增加TF定义
$ roscd turtlebot_navigation
$ mkdir -p laser/driver
$ sudo cp ~/turtlebot_ws/src/flashgo/launch/lidar.launch laser/driver/flashlidar_laser.launch
- 打开flashgolidar_laser.launch,并修改
$ rosed turtlebot_navigation flashlidar_laser.launch
- 检查frame_id是否指定为laser
<param name="frame_id" type="string" value="laser"/>
- 查看serial_port是否指定正确端口,使用别名
- 检查端口:
<param name="serial_port" type="string" value="/dev/flashlidar"/>
,设置好别名. - 增加TF:
<node pkg="tf" type="static_transform_publisher" name="base_to_laser" args="0.0 0.0 0.18 0 0.0 0.0 base_link laser 100"/>
修改为args="0.0 0.0 0.18 0 0.0 0.0 为自己的实际安装位置。详情查看,static_transform_publisher部分
static_transform_publisher x y z qx qy qz qw frame_id child_frame_id period_in_ms
这里我假设底盘的中心点为0,雷达放在机器人托盘中心位置,X为0,高度为18CM,Z为0.18m
TF的单位使用米的,测量单位是CM
完整代码如下:
<launch>
<node name="flashgo_node" pkg="flashgo" type="flashgo_node" output="screen">
<param name="serial_port" type="string" value="/dev/flashlidar"/>
<param name="serial_baudrate" type="int" value="115200"/>
<param name="frame_id" type="string" value="laser"/>
<param name="angle_compensate" type="bool" value="true"/>
<param name="ignore_array" type="string" value="" />
<param name="ignore_value" type="double" value="0" />
</node>
<node pkg="tf" type="static_transform_publisher" name="base_to_laser" args="0.0 0.0 0.18 0 0.0 0.0 base_link laser 100"/>
</launch>
检查turtlebot_navigation包
- 增加flashlidar_hector_mapping_demo.launch文件,用于启动hector
$ roscd turtlebot_navigation
$ touch launch/flashlidar_hector_mapping_demo.launch
$ rosed launch/flashlidar_hector_mapping_demo.launch
- 输入内容:
<launch>
<!-- Define laser type-->
<arg name="laser_type" default="flashlidar" />
<!-- laser driver -->
<include file="$(find turtlebot_navigation)/laser/driver/$(arg laser_type)_laser.launch" />
<!-- Gmapping -->
<arg name="custom_gmapping_launch_file" default="$(find turtlebot_navigation)/launch/includes/hector_mapping/$(arg laser_type)_hector_mapping.launch.xml"/>
<include file="$(arg custom_gmapping_launch_file)"/>
<!-- Move base -->
<include file="$(find turtlebot_navigation)/launch/includes/move_base.launch.xml"/>
</launch>
设置laser_type为flashlidar.
增加flashlidar_hector_mapping.launch.xml文件,执行hector建图
$ roscd turtlebot_navigation
$ touch launch/includes/hector_mapping/flashlidar_hector_mapping.launch.xml
$ rosed launch/includes/hector_mapping/flashlidar_hector_mapping.launch.xml
- 输入内容:
<launch>
<node pkg="hector_mapping" type="hector_mapping" name="hector_mapping" output="screen">
<!-- Frame names -->
<param name="pub_map_odom_transform" value="true"/>
<param name="map_frame" value="map" />
<param name="scan_topic" value="scan" />
<param name="base_frame" value="base_footprint"/>
<param name="odom_frame" value="odom"/>
<!-- Tf use -->
<param name="use_tf_scan_transformation" value="true"/>
<param name="use_tf_pose_start_estimate" value="false"/>
<!-- Map size / start point -->
<param name="map_resolution" value="0.05"/>
<param name="map_size" value="2048"/>
<param name="map_start_x" value="0.5"/>
<param name="map_start_y" value="0.5" />
<param name="laser_z_min_value" value = "-1.0" />
<param name="laser_z_max_value" value = "1.0" />
<param name="map_multi_res_levels" value="2" />
<param name="map_pub_period" value="2" />
<param name="laser_min_dist" value="0.4" />
<param name="laser_max_dist" value="5.5" />
<param name="output_timing" value="false" />
<param name="pub_map_scanmatch_transform" value="true" />
<!--<param name="tf_map_scanmatch_transform_frame_name" value="scanmatcher_frame" />-->
<!-- Map update parameters -->
<param name="update_factor_free" value="0.4"/>
<param name="update_factor_occupied" value="0.7" />
<param name="map_update_distance_thresh" value="0.2"/>
<param name="map_update_angle_thresh" value="0.06" />
<!-- Advertising config -->
<param name="advertise_map_service" value="true"/>
<param name="scan_subscriber_queue_size" value="5"/>
</node>
</launch>
测试激光雷达hector构建地图
- 上网本新开端口,打开roscore
$ roscore
- 上网本新开端口,启动turtlebot
$ roslaunch turtlebot_bringup minimal.launch
- 上网本新开端口,启动hector,用于构建地图
$ roslaunch turtlebot_navigation flashlidar_hector_mapping_demo.launch
- 工作机或上网本新开端口,启动键盘操作Turtlebot
$ roslaunch turtlebot_teleop keyboard_teleop.launch
- 工作机或上网本新开端口,启动rviz,实时查看建图情况
$ roslaunch turtlebot_rviz_launchers view_navigation.launch
构建地图结束保存地图
- 上网本新开端口,建立目录,保存地图
$ mkdir -p ~/map
$ rosrun map_server map_saver -f ~/map/flashlidar_hector_mapping
$ ls ~/map #查看内容,包含flashlidar_hector_mapping.pgm flashlidar_hector_mapping.yaml
- 查看地图,已经生成flashlidar_hector_mapping.pgm文件,可以用图像浏览器(gimp, eog, gthumb, 等等)打开查看。
利用地图进行AMCL
获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号