用自己的雷达进行Cartographer建图或仿真

首先需要进行Cartographer安装以及雷达驱动安装等准备工作, 直至我们能够在雷达运行时找到发布LaserScan的Topic并获取数据, 以开始下一步的建图.

基本信息获取

启动雷达或gazebo, 在终端使用以下语句查看雷达输出的Topic:
rostopic list;

此处本天河雷达的输出topic为 /radar_real
使用以下语句打印当前雷达输出:
rostopic echo /radar_real;

在打印信息中找到坐标系名字frame_id: “base_laser”,此处坐标系名字为 base_laser

lua文件修改

在(cartographer工作空间)/src/cartographer_ros/cartographer_ros/configuration_files中找到revo_lds.lua 文件, 复制一份, 改名为my_revo_lds.lua.
打开my_revo_lds.lua, 修改以下两行为我们自己的坐标系名字:

//两行"horizontal_laser_link"均改为我们当前的"base_laser"
tracking_frame = "horizontal_laser_link",
published_frame = "horizontal_laser_link",
launch文件修改

在(cartographer工作空间)/src/cartographer_ros/cartographer_ros/launch中找到demo_revo_lds.launch, 复制一份, 改名为my_demo_revo_lds.launch
修改以下内容:

//因为非bag仿真,将以下true改为false
<param name="/use_sim_time" value="true" />

//使用我们的配置文件,将revo_lds.lua改为my_revo_lds.lua
<node name="cartographer_node" pkg="cartographer_ros"
      type="cartographer_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename revo_lds.lua"

//将horizontal_laser_2d改为我们的输出话题radar_real
<remap from="scan" to="horizontal_laser_2d" />

//不使用bag,删去以下内容
<node name="playbag" pkg="rosbag" type="play"
      args="--clock $(arg bag_filename)" />
运行与建图

对修改后的工作空间, 在终端执行以下语句以重编译:

//编译cartographer工作空间
catkin_make_isolated --install --use-ninja

//刷新环境
source devel_isolated/setup.bash

运行时, 先运行雷达的相关topic, 保证雷达已有有效数据通过topic输出后, 运行我们的新launch文件:
roslaunch cartographer_ros my_demo_revo_lds.launch

即可开始建图.

地图保存

打开另一个终端, 输入以下语句:

//结束第一条轨迹,之后的数据不再添加.
rosservice call /finish_trajectory 0

//cartographer序列化当前状态,形成pbstream文件
rosservice call /write_state "{filename: '${HOME}/Downloads/mymap.pbstream'}"

//transform pbstream to pgm and yaml

rosrun cartographer_ros cartographer_pbstream_to_ros_map -map_filestem=/home/kai/Downloads/mymap -pbstream_filename=/home/kai/Downloads/mymap.pbstream -resolution=0.05

地址和文件名根据实际进行修改.

运行结果

纯雷达建图.

  • 天河
    在天河10Hz 2880点的雷达上, 建图极易漂移, 无法完成建图. 期间频繁报 "Dropped 2770 earlier points."的警告, 该warning来自于:
    range_data_collator.cc:76 LOG(WARNING) << “Dropped " << std::distance(ranges.begin(), overlap_begin) << " earlier points.”;
    丢点数值常在2700左右变动, 接近于一帧.

  • 倍加福
    在倍加福20Hz 3600点的雷达上, 无警告提示, 建图顺滑, 匹配准确, 旋转鲁棒性好, 建图质量佳, 仅在特征不明显的长走廊出现建图尺度失真的共性问题.

  • 思岚rplidar a2
    在思岚科技RPLIDAR-a2(10Hz 800点)上, 建图顺滑, 但限于雷达硬件, 旋转速度不宜过快, 建图过程应当尽量保持雷达速度平稳. [Topic Name: /scan; Frame Name: laser]
    (a2驱动安装传送门: 只需关注其中rplida相关步骤)(链接教程勘误: echo source时删去那对双引号)

  • gazebo仿真
    因为依然不是bag仿真, 上述设置/use_sim_time依然应该是false.

  • 6
    点赞
  • 57
    收藏
    觉得还不错? 一键收藏
  • 6
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 6
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值