ROS Group 产品服务
Product Service 开源代码库
Github 官网
Official website 技术交流
Technological exchanges 激光雷达
LIDAR ROS教程
ROS Tourials 深度学习
Deep Learning 机器视觉
Computer Vision
小强ROS机器人教程(16)___大范围激光雷达slam与实时回路闭合测试
-
借助谷歌的Cartographer配合slamtec的激光雷达,我们可以尝试对大型建筑建立平面图。先看我们自己的demo演示效果。
在本demo中,小强实际运行在一个5000平米的写字楼走廊里,走廊两侧存在大量的玻璃幕墙,大楼中央存在一个大面积空旷地,加上rplidar的测距范围只有6米,因此下图的最终效果还算理想(只使用激光雷达,没有开启IMU和底盘odometer,大回路路径仍然成功闭合)
本文操作思路:因为是大范围建图,wifi网络覆盖是一个问题,所以我们借助蓝牙手柄来遥控小车运动。期间通过rosbag录制激光雷达数据,手柄遥控小车在建图范围内跑一圈,最后重放bag建图。
注:以下所有操作在小车主机ubuntu上完成
准备工作:
1.安装rplidar驱动
对于2016年11月15日之后购买小强开发平台的用户,rplidar驱动已经配置好。
rplidar的驱动安装请参考这篇教程2.安装ps3手柄驱动
对于2016年11月15日之后购买小强开发平台的用户,请跳过本步骤。
请参考这篇安装教程3.安装cartographer_ros
请参考这篇安装教程:http://community.bwbot.org/topic/136/google激光雷达slam算法cartographer的安装及bag包demo测试
操作步骤:
1.新开一个窗口启动rplidar
roslaunch rplidar_ros rplidar.launch
2.新开两个窗口启动ps3手柄遥控程序,按手柄连接键连上小车
第一个窗口sudo bash rosrun ps3joy ps3joyfake_node.py
第二个窗口
roslaunch turtlebot_teleop ps3fakexiaoqiang_teleop.launch
3.新开一个窗口启动rosbag录制进程,开始录制激光雷达数据/scan
rosbag record /scan
4.用手柄遥控小车运动,绕建图区域一圈,也可以多圈
5.bag录制完成,关闭上文的1、2、3窗口
新录制的点bag文件在小强home目录下,将其重命名为1.bag6.启动cartographer_ros开始bag回放建图
roslaunch cartographer_ros demo_xiaoqiang_rplidar_2d.launch bag_filename:=/home/xiaoqiang/1.bag
7.一切正常的话,现在可以看到下图的类似效果,等待bag包play完
8.用map_server保存地图,本文结束
rosrun map_server map_saver --occ 51 --free 49 -f work0
-
这个模型看起来很性感!
-
自动修正很棒啊!大牛大牛!
-
@xiaoqiang 你好,
我在复现您的步骤6(启动cartographer_ros开始bag回放建图)发现自带的测试.launch并不能回放并且建图。
我注意到您在这里使用的是
roslaunch cartographer_ros demo_xiaoqiang_rplidar_2d.launch bag_filename:=/home/xiaoqiang/1.bag
demo_xiaoqiang_rplidar_2d.launch。 请问如何修改launch文件才能达到如您贴中所示的建图的效果呢?这个文件可以提供么?谢谢!
期待您的回复!
mail: jwzhang86@gmail.com -
@buptvv 按照步骤3安装完成后就会有那个launch文件。 这个bag文件是我们自己录制的,所以launch文件根据这个bag的topic进行了调整。
<!-- Copyright 2016 The Cartographer Authors Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License. --> <launch> <param name="/use_sim_time" value="true" /> <!-- <node pkg="tf" type="static_transform_publisher" name="base_laser_broadcaster" args="0 0 0 0 0 0 laserbase_footprint /base_footprint 20" /> --> <include file="$(find cartographer_ros)/launch/rplidar_2d.launch" /> <node name="cartographer_node" pkg="cartographer_ros" type="cartographer_node" args=" -configuration_directory $(find cartographer_ros)/configuration_files -configuration_basename xiaoqiang_rplidar_2d.lua" output="screen"> <remap from="/odom" to="/xqserial_server/Odom" /> </node> <node name="rviz" pkg="rviz" type="rviz" required="true" args="-d $(find cartographer_ros)/configuration_files/rplidar_2d.rviz" /> <node name="playbag" pkg="rosbag" type="play" args="--clock $(arg bag_filename)" /> </launch>
-
@xiaoqiang 在 小强ROS机器人教程(16)___大范围激光雷达slam与实时回路闭合测试 中说:
rosbag record /scan
bag包只需要录制激光雷达的数据就够了吗?然后直接交给cartographer 就可以回放制图了?
如果这样的话,是不是用小强的bag包也可以在另外的PC上回放制图呢?谢谢。
-
@山中客 是这样的
-
@xiaoqiang 在 小强ROS机器人教程(16)___大范围激光雷达slam与实时回路闭合测试 中说:
一切正常的话,现在可以看到下图的类似效果,等待bag包play完
回放建图失败了。如图rviz显示和log:
bag有效性检查,有如下提示:
不知道问题出在什么地方,另外我使用的小强雷达是倒着装的(雷达沿x轴旋转180度),能否帮忙看看,谢谢!
-
@山中客 问题定位到了,关键提示:Fixed Frame [map] does not exist.
小强配置的frame id是[map_laser], 之前改过调试的时候这个地方给改成了map,导致rviz回放转换地图失败了。