在调试cartographer算法代码及参数的时候,如果每次都连接真实的智能轮椅,会很麻烦,需要做很多准备工作,且有某个环节出现问题,都会影响到机器人的运行,最终导致算法不具备运行条件。
本文描述了事先从智能轮椅上采集好所需话题数据,然后利用cartographer离线建图和定位。

1数据采集

运行产生数据的节点

运行激光雷达节点

roslaunch urg_node urg_lidar.launch 

rosbag记录数据

记录全部话题

rosbag record -a

记录部分话题

rosbag record /scan /imu /odom

2 cartographer离线建图

2.1 快速建图

该方法有点是运行耗时很短,缺点是中间过程看的不清晰。
编写launch文件:offline_wheelchair_2d.launch
在实际应用中需要将#注释去掉。

<launch>
   # 是否启用rivz
  <arg name="no_rviz" default="false"/>
  # 是否启动仿真模式
  <param name="/use_sim_time" value="true" />

  <group unless="$(arg no_rviz)">
    <node name="rviz" pkg="rviz" type="rviz" required="true"
        args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />

    <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
        type="cartographer_occupancy_grid_node" args="-resolution 0.05" />
  </group>

 # 启动离线建图的节点
  <node name="cartographer_offline_node" pkg="cartographer_ros"
      required="$(arg no_rviz)"
      type="cartographer_offline_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files    # 配置文件路径
          -configuration_basenames my_backpack_2d.lua								# 配置文件名称
          -urdf_filenames $(find cartographer_ros)/urdf/my_robot_2d.urdf			# 机器人描述文件
          -bag_filenames $(arg bag_filenames)"									# 录制数据包的路径及文件名参数
      output="screen">
    <remap from="scan" to="scan" />
  </node>
</launch>

编写配置文件my_backpack_2d.lua:


include "map_builder.lua"
include "trajectory_builder.lua"

options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",                          # 总坐标系:map
  tracking_frame = "base_link",
  published_frame = "base_footprint",  -- odom  # 发布的tf坐标系名称?
  odom_frame = "odom",

  provide_odom_frame = true, -- false    #对外提供里程信息?
  publish_frame_projected_to_2d = true,

  use_odometry = false,
  use_nav_sat = false,
  use_landmarks = false,

  num_laser_scans = 1,
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 10,
  num_point_clouds = 0,

  lookup_transform_timeout_sec = 0.2,
  submap_publish_period_sec = 0.3,
  pose_publish_period_sec = 5e-3,
  trajectory_publish_period_sec = 30e-3,
  rangefinder_sampling_ratio = 1.,
  odometry_sampling_ratio = 1.,
  fixed_frame_pose_sampling_ratio = 1.,
  imu_sampling_ratio = 1.,
  landmarks_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_2d = true
TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 10
TRAJECTORY_BUILDER_2D.use_imu_data = false

POSE_GRAPH.optimization_problem.local_slam_pose_translation_weight = 1e5
POSE_GRAPH.optimization_problem.local_slam_pose_rotation_weight = 1e5
POSE_GRAPH.optimization_problem.odometry_translation_weight = 1e4
POSE_GRAPH.optimization_problem.odometry_rotation_weight = 1e4

return options

启动方法:在终端输入以下命令

roslaunch cartographer_ros offline_wheelchair_2d.launch bag_filenames:=${HOME}/2020-08-14-15-54-03.bag

运行完成后,就会在数据包的同目录下生成同名地图:2020-08-14-15-54-03.bag.pbstream。
地图格式转换

rosrun cartographer_ros cartographer_pbstream_to_ros_map  -map_filestem=${HOME}/zzz_usr_mapname  -pbstream_filename=${HOME}/2020-08-14-15-54-03.bag.pbstream -resolution=0.05

将会声名称为zzz_usr_mapname的文件,成功后终端提示信息如下:

I0817 17:31:03.804515 17965 pbstream_to_ros_map_main.cc:50] Loading submap slices from serialized data.
I0817 17:31:03.995290 17965 pbstream_to_ros_map_main.cc:70] Generating combined map image from submap slices.

2.2 常规速度建图

此方法与用实物智能轮椅建图过程一致,可看清楚中间过程。
编写文件:demo_wheelchair_2d.launch

<launch>
  <param name="/use_sim_time" value="true" />

  <include file="$(find cartographer_ros)/launch/wheelchair_2d.launch" />

  <node name="playbag" pkg="rosbag" type="play"
      args="--clock $(arg bag_filename)" />
</launch>

其中引用的文件wheelchair_2d.launch为常规的建图启动文件:


<launch>
  <param name="robot_description"
    textfile="$(find cartographer_ros)/urdf/my_robot_2d.urdf" />

  <node name="robot_state_publisher" pkg="robot_state_publisher"
    type="robot_state_publisher" />

  <node name="cartographer_node" pkg="cartographer_ros"
      type="cartographer_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename my_backpack_2d.lua"
      output="screen">
    <remap from="scan" to="scan" />
  </node>

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
    type="cartographer_occupancy_grid_node" args="-resolution 0.05" />

  <node name="rviz" pkg="rviz" type="rviz" required="true"
    args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
</launch>

启动命令

roslaunch cartographer_ros demo_wheelchair_2d.launch bag_filename:=${HOME}/2020-08-14-15-54-03.bag

离线数据播放完毕后,终端会有提示:

[playbag-6] process has finished cleanly

终点输入命令,结束建图任务:

rosservice call /finish_trajectory 0

保存当前地图

rosservice call /write_state "{filename: '${HOME}/Downloads/mymap_name.pbstream'}"

地图格式转换

rosrun cartographer_ros cartographer_pbstream_to_ros_map  -map_filestem=${HOME}/Downloads/mymap_name  -pbstream_filename=${HOME}/Downloads/mymap_name.pbstream -resolution=0.05

3 cartographer离线定位

编写launch文件:demo_wheelchair_2d_localization.launch

<launch>
  <param name="/use_sim_time" value="true" />

  <param name="robot_description"
    textfile="$(find cartographer_ros)/urdf/my_robot_2d.urdf" />

  <node name="robot_state_publisher" pkg="robot_state_publisher"
    type="robot_state_publisher" />

  <node name="cartographer_node" pkg="cartographer_ros"
      type="cartographer_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename my_backpack_2d_localization.lua
          -load_state_filename $(find cartographer_ros)/maps/curve_level2_circle1.pbstream"     # 加载已存在地图
      output="screen">   
  </node>

  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05" />

  <node name="rviz" pkg="rviz" type="rviz" required="true"
      args="-d $(find cartographer_ros)/configuration_files/demo_2d.rviz" />
  <node name="playbag" pkg="rosbag" type="play"  
      args="--clock $(arg bag_filename)" />   # 播放ros数据包
</launch>

其中所依赖文件my_backpack_2d_localization.lua为常规定位的配置文件:

include "my_backpack_2d.lua"
 
TRAJECTORY_BUILDER.pure_localization = true

POSE_GRAPH.optimize_every_n_nodes = 20  -- 每90个有效帧一个子图,子图构建完成要闭环检测一次,这个数越小,闭环检测越频繁,当然CPU爆炸

TRAJECTORY_BUILDER_2D.ceres_scan_matcher.ceres_solver_options.num_threads = 4
POSE_GRAPH.constraint_builder.ceres_scan_matcher.ceres_solver_options.num_threads = 4
MAP_BUILDER.num_background_threads = 8

return options

启动指令

roslaunch cartographer_ros demo_wheelchair_2d_localization.launch    bag_filename:=${HOME}/2020-08-14-14-23-16.bag 
Logo

DAMO开发者矩阵,由阿里巴巴达摩院和中国互联网协会联合发起,致力于探讨最前沿的技术趋势与应用成果,搭建高质量的交流与分享平台,推动技术创新与产业应用链接,围绕“人工智能与新型计算”构建开放共享的开发者生态。

更多推荐