描述

关于cartographer的学习笔记

DEMO运行

launch文件详解

以下是官网给出的demo执行命令

roslaunch cartographer_ros demo_backpack_2d.launch bag_filename:=${HOME}/Downloads/cartographer_paper_deutsches_museum.bag

1. demo_backpack_2d.launch文件

内容如下

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

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

  <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)" />
</launch>

launch文件的含义是

由于是仿真,所以设置/use_sim_time为true
include的意思是,嵌套复用backpack_2d.launch
启动rviz,并通过required="true"设置rviz为必要节点,rviz挂了其他节点也会被终止。
-d的含义是运行指定的.rviz文件
启动数据包回放功能,--clock是回放指定的数据包
2. 嵌套复用的backpack_2d.launch
文件内容如下

<launch>
  <param name="robot_description"
    textfile="$(find cartographer_ros)/urdf/backpack_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 backpack_2d.lua"
      output="screen">
    <remap from="echoes" to="horizontal_laser_2d" />
  </node>

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

launch文件的含义是

textfile加载指定的描述文件,使用命令rosparam get /robot_description可以在shell看到,整个backpack_2d.urdf文件的内容,相当于robot_description被设置成了指定的描述文件
configuration_directory和configuration_basename是命令行需要传递的参数的关键字
写服务程序时,如果需要提供命令行参数。传统的方法是手工解析argv参数,或者使用getopt函数。两种方法都比较费劲。使用Google gflags可以大大简化命令行参数处理

你会发现在cartographer_ros/node_main.cc文件中存在

#include "gflags/gflags.h"

DEFINE_string(configuration_directory, "",
              "First directory in which configuration files are searched, "
              "second is always the Cartographer installation to allow "
              "including files from there.");
DEFINE_string(configuration_basename, "",
              "Basename, i.e. not containing any directory prefix, of the "
              "configuration file.");

意思就是,roslaunch文件中的内容会赋值给程序,显然赋值到程序中的是两个代表路径和文件名字的字符串$(find cartographer_ros)/configuration_files和backpack_2d.lua,得到赋值的变量名字会写成FLAGS_configuration_directory和FLAGS_configuration_basename

remap的意思是把 /echoes 的话题重映射到 /horizontal_laser_2d话题,使用命令
rosnode info /cartographer_node可以看得到节点cartographer_node订阅了/horizontal_laser_2d话题

Node [/cartographer_node]
Publications: 
 * /constraint_list [visualization_msgs/MarkerArray]
 * /landmark_poses_list [visualization_msgs/MarkerArray]
 * /rosout [rosgraph_msgs/Log]
 * /scan_matched_points2 [sensor_msgs/PointCloud2]
 * /submap_list [cartographer_ros_msgs/SubmapList]
 * /tf [tf2_msgs/TFMessage]
 * /trajectory_node_list [visualization_msgs/MarkerArray]

Subscriptions: 
 * /clock [rosgraph_msgs/Clock]
 * /horizontal_laser_2d [sensor_msgs/MultiEchoLaserScan]
 * /imu [sensor_msgs/Imu]
 * /tf [tf2_msgs/TFMessage]
 * /tf_static [tf2_msgs/TFMessage]

-resolution和上面一样,代表地图分辨率,在函数cartographer_ros/occupancy_grid_node_main.cc中处理