导航

    蓝鲸ROS机器人论坛

    • 注册
    • 登录
    • 搜索
    • 版块
    • 话题
    • 热门
    ROS交流群
    ROS Group
    产品服务
    Product Service
    开源代码库
    Github
    官网
    Official website
    技术交流
    Technological exchanges
    激光雷达
    LIDAR
    ROS教程
    ROS Tourials
    深度学习
    Deep Learning
    机器视觉
    Computer Vision

    谷歌cartographer使用速腾聚创3d激光雷达转二维数据进行2d建图

    激光雷达
    激光雷达
    3
    5
    5176
    正在加载更多帖子
    • 从旧到新
    • 从新到旧
    • 最多赞同
    回复
    • 在新帖中回复
    登录后回复
    此主题已被删除。只有拥有主题管理权限的用户可以查看。
    • xiaoqiang
      xiaoqiang 最后由 xiaoqiang 编辑

      谷歌cartographer_ros请参考这篇安装教程:http://community.bwbot.org/topic/136/google激光雷达slam算法cartographer的安装及bag包demo测试

      1. 数据包准备

      本文建图将采用普通的2d 雷达数据,结合IMU和里程计数据进行2d建图。2d 雷达数据由速腾聚创3d激光雷达转换得到,其他数据由小强机器人底盘得到。
      rosbag数据包的详细制作过程,请参考这篇教程: https://community.bwbot.org/topic/522/使用rosbag录制和回放3d激光雷达数据和小强ros开发平台的里程计imu数据
      下文教程将以蓝鲸机器人录制的bag包为例,演示如何建立2d地图。bag包百度云下载地址

      2. 配置cartographer_ros

      蓝鲸机器人github上的cartographer_ros已经配置好了所有文件,对于加装速腾聚创小强xq5开发平台采集的数据包,cartographer_ros需要使用的是下列文件,简略的说明在下文。cartographer_ros的详细文档可以参考官方wiki

      cartographer_ros/launch/demo_xiaoqiang_rslidar_scan.launch #建图时启动的launch文件,负责启动rviz,加载cartographer_ros主要的启动节点和参数文件,话题数据名字的remap也在这个文件设定。
      
      cartographer_ros/urdf/rslidar_2d.urd #模型文件,用来发布3d激光雷达、小车里程计、IMU、小车本体之间的tf关系
      
      cartographer_ros/configuration_files/xiaoqiang_rslidar_scan.lua #cartographer_ros算法参数配置文件,优化建图效果需要调整的参数就是这个文件。
      

      ros中坐标系的设置,请参考这篇教程,小强xq5平台的base_link原点设置在两个主动轮轴中间位置。

      # cartographer_ros/configuration_files/xiaoqiang_rslidar_scan.lua文件里面设置是否使用imu、odom数据的参数是这两个:
      use_odometry = true  #true使能里程计,false禁用里程计
      TRAJECTORY_BUILDER_2D.use_imu_data = false  #true使能IMU,false禁用IMU
      
      # cartographer_ros)/urdf/rslidar_2d.urd文件需要调整的参数是3d雷达相对base_link的安装位置,laserbase_link等价于base_link
      <joint name="horizontal_laser_link_joint" type="fixed">
          <parent link="laserbase_link" />
          <child link="rslidar" />
          <origin xyz="0 0 0.4" rpy="0 0 0" />
        </joint>
      

      3. 启动cartographer_ros,播放rosbag数据包,开始建图

      #先关闭小车的ros启动节点
      #在小车主机上新开一个命令终端
      sudo service startup stop
      roscore
      
      #启动cartographer
      #在小车主机上新开一个命令终端
      roslaunch cartographer_ros demo_xiaoqiang_rslidar_scan.launch 
      
      #播放bag数据
      #在小车主机上新开一个命令终端
      rosbag play  --clock  2018-08-11-13-20-34.bag
      

      0_1534137389985_scan_1.png
      0_1534137402544_Screenshot from 2018-08-13 13-14-09.png
      0_1534137413409_Screenshot from 2018-08-13 13-16-04.png
      0_1534137441815_Screenshot from 2018-08-11 20-08-13.png

      4. bag播放完成后,用map_server保存地图

      rosrun map_server map_saver --occ 51 --free 49 -f work0
      

      保存成功后,会在home目录里面生成work0.yaml work0.pgm两个地图文件,这两个文件可以用来amcl导航。

      Duke-Allen 1 条回复 最后回复 回复 引用 0
      • Duke-Allen
        Duke-Allen @xiaoqiang 最后由 编辑

        @xiaoqiang您好,请问如果只用雷达数据来进行2D建图的话,cartographer_ros应该怎么配置呢?

        xiaoqiang 1 条回复 最后回复 回复 引用 0
        • xiaoqiang
          xiaoqiang @Duke-Allen 最后由 编辑

          @Duke-Allen

          # cartographer_ros/configuration_files/xiaoqiang_rslidar_scan.lua文件里面设置是否使用imu、odom数据的参数是这两个:
          use_odometry = true  #true使能里程计,false禁用里程计
          TRAJECTORY_BUILDER_2D.use_imu_data = false  #true使能IMU,false禁用IMU
          
          zhaoyu24 1 条回复 最后回复 回复 引用 0
          • zhaoyu24
            zhaoyu24 @xiaoqiang 最后由 编辑

            @xiaoqiang 只使用雷达数据的话,tf的关系还需要修改吗?

            xiaoqiang 1 条回复 最后回复 回复 引用 0
            • xiaoqiang
              xiaoqiang @zhaoyu24 最后由 编辑

              @zhaoyu24 雷达数据所在frame到tracking frame之间的tf必须提供

              1 条回复 最后回复 回复 引用 0
              • 1 / 1
              • First post
                Last post
              Copyright © 2015-2023 BlueWhale community