cartographer探索记录


Cartographer探索笔记

Lua配置文件参数解析

参数解析常用值
map_frame用于发布submaps的ROS坐标系ID,位姿的父坐标系,通常使用“map”“map”
tracking_frame由SLAM算法追踪的ROS坐标系ID,如果使用IMU,应该使用其坐标系,通常选择是 “imu_link”"base_footprint"
published_frame用于发布位姿子坐标系的ROS坐标系ID,例如“odom”坐标系,如果一个“odom”坐标系由系统的不同部分提供,在这种情况下,map_frame中的“odom”姿势将被发布。 否则,将其设置为“base_link”可能是合适的"odom"
odom_frame在provide_odom_frame为真才启用,坐标系在published_frame和map_frame之间用于发布局部SLAM结果,通常是“odom”"odom"
provide_odom_frame如果启用,局部,非闭环,持续位姿会作为odom_frame发布在map_frame中发布。true
use_odometry如果启用,订阅关于“odom”话题的nav_msgs/Odometry消息。里程信息会提供,这些信息包含在SLAM里false
num_laser_scans

订阅的激光扫描话题数量。

在一个激光扫描仪的“scan”话题上订阅sensor_msgs/LaserScan

或在多个激光扫描仪上订阅话题“scan_1”,“scan_2”等

1
num_multi_echo_laser_scans

订阅的多回波激光扫描主题的数量。

在一个激光扫描仪的“echoes”话题上订阅sensor_msgs/MultiEchoLaserScan

或者为多个激光扫描仪订阅话题“echoes_1”,“echoes_2”等。

0
num_subdivisions_per_laser_scan

将每个接收到的(多回波)激光扫描分成的点云数。

细分扫描可以在扫描仪移动时取消扫描获取的扫描。

有一个相应的轨迹构建器选项可将细分扫描累积到将用于扫描匹配的点云中。

1
num_point_clouds

要订阅的点云话题的数量。

在一个测距仪的“points2”话题上订阅sensor_msgs/PointCloud2

或者为多个测距仪订阅话题“points2_1”,“points2_2”等。

0

lookup_transform_timeout_sec

使用tf2查找变换的超时秒数0.2
submap_publish_period_sec发布submap的间隔(以秒为单位),例如, 0.3秒0.3
pose_publish_period_sec发布姿势的间隔(以秒为单位),例如 5e-3,频率为200 Hz。5e-3

trajectory_publish_period_sec

以秒为单位发布轨迹标记的时间间隔,例如, 30e-3持续30毫秒30e-3

urdf文件中的一些问题

  • 把所有的坐标系转化到一起去没用,相机和雷达本身的坐标系是什么样子的,就应该在urdf中描述成什么样子。

  • urdf中的rpy是绕xyz轴旋转,并且是定轴!!!

    绕动轴z-y-x旋转的是Euler角(ypr)

  • imu和雷达是绑定的,转一个的坐标系,另外一个也会跟着转

使用cartographer建图

建图、导入保存本地的地图、导入地图时带入初始的位姿

保存地图到本地

1、Finish the first trajectory. No further data will be accepted on it.

rosservice call /finish_trajectory 0

2、Ask Cartographer to serialize its current state.

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

3、transform pbstream to pgm and yaml

roslaunch cartographer_ros assets_writer_ros_map.launch bag_filenames:=${HOME}/Downloads/***.bag pose_graph_filename:=${HOME}/Downloads/***.pbstream

or

rosrun cartographer_ros cartographer_pbstream_to_ros_map -map_filestem=/home/lqx/Downloads/savemap -pbstream_filename=/home/lqx/Downloads/***.pbstream -resolution=0.05

从本地导入地图

cartographer pure localization

<node name="cartographer_node" pkg="cartographer_ros" type="cartographer_node" args="-load_state_filename $MAP_NAME.pbstream" />

下面这个不太清楚,似乎不需要

TRAJECTORY_BUILDER.pure_localization = true

带入初始位姿信息

cartographer pure localization initial pose

在launch文件中加入 -start_trajectory_with_default_topics=false,最后的效果如下所示:

  <node name="cartographer_node"
        pkg="cartographer_ros"
        type="cartographer_node"
        args="
-configuration_directory $(find cartographer_ros_launcher)/configuration_files 
-configuration_basename cartographer.lua 
-load_state_filename /home/lqx/Downloads/2021_map.pbstream 
-start_trajectory_with_default_topics=false
"
        output="screen">
  </node>

设置初始位姿时,需要注意四元数的归一化,并且map坐标是建图的时候就确定了的。使用的指令如下:

rosservice call /start_trajectory "configuration_directory: '/home/lqx/catkin_cv/src/cartographer_ros_launcher/configuration_files'
configuration_basename: 'cartographer.lua'
use_initial_pose: true
initial_pose:
  position: {x: 1.0, y: -1.5, z: 0.0}
  orientation: {x: 0, y: 0, z: 0, w: 1}
relative_to_trajectory_id: 0"

多机协同,共用一张地图

问题描述

  • 单机器人的闭环检测,修正误差累计,保证地图一致性
  • 实现场景识别,从而建立多机器人间的约束
  • 压缩地图数据,使其满足带宽有限的机器人间的数据共享

To be continued……


文章作者: Immortalqx
版权声明: 本博客所有文章除特別声明外,均采用 CC BY 4.0 许可协议。转载请注明来源 Immortalqx !
评论
  目录