第一步 了解bag文件
播放 bag 文件需要在 bag 的文件夹内启动五个终端
- 第一个终端执行 roscore
- 第二个终端执行 rosbag info rslidar-outdoor-gps.bag
了解 bag 中 topic 的名称与类型
- 第三个执行 rosbag play rslidar-outdoor-gps.bag
- 第四个终端执行 rqt
- 了解 bag 中的 tf 树
- 注意, rqt 的所有显示插件都在菜单栏的 plugins 内, 再点击 visualization, 再点击 tf tree, 即可显示视频中的 tf 树的可视化界面.
- 第五个终端执行 rviz
- 可视化雷达数据与 tf 数据.
- rviz 左侧最顶上的 Fixed frame 除了下拉菜单可以选择之外, 还是可以手动输入的, 现在手动输入成 odom ,
- rviz 左侧下方的 Add 按钮, 可以添加显示的插件, 自己选择添加 pointcloud2, laserscan 等格式的数据, 之后把插件订阅的 topic 选择一下, 如果不会就自己摸索一下, 很简单的.
第二步 配置 launch 文件
launch 文件中需要如下几个设置
- bag 文件的地址与 bag 文件的名字
- lua 文件的名字
- topic 需要 remap 成 bag 文件中发布的 topic
第三步 配置 lua 文件
- tracking_frame 有 imu 的 link 就设置成 imu 的 link, 没有就设置成 base_link
- published_frame cartographer 发布的 tf 的最下边一个坐标系, 就是 bag 文件中 tf 树的最上边的一个坐标系
- provide_odom_frame 是否提供里程计, 如果 bag 中有里程计的坐标系, 这个就是 false, 如果没有, 就根据需要决定是否提供里程计的坐标系
- use_pose_extrapolator = false 这个一定要设置成 false
- use_odometry 是否使用里程计的传感器数据, 如果为 true, tf 树中一定要存在 odom 这个坐标系
- use_nav_sat/use_landmarks 是否订阅里程计话题的数据, 以及 landmark话题的数据
- num_laser_scans/num_point_clouds 单线点云与多线点云的话题的数量, 可以同时为1, 不可以同时为
- num_subdivisions_per_laser_scan 一帧点云数据会被分成几次处理, 设置成 1 就行了
- MAP_BUILDER.use_trajectory_builder_2d = true 建二维图时一定要有这句话, 建三维图就把 2d 改成 3d
- TRAJECTORY_BUILDER_2D.use_imu_data 是否使用 imu, 如果用 imu, tracking_frame 一定要设置成 imu 的 link
- TRAJECTORY_BUILDER_2D.min_z 点云的最小 z 的范围, 单线点云不能设置大 于 0 的值(不设置), 多线点云的这个值要大于 0
仿真环境下使用cartographer建图的demo演示:
launch文件:
/home/lxy/carto_ws/cartographer_detailed_comments_ws/src/cartographer_ros/cartographer_ros/launch/test01.launch
<launch>
<param name="/use_sim_time" value="true" />
<node name="cartographer_node" pkg="cartographer_ros"
type="cartographer_node" args="
-configuration_directory $(find cartographer_ros)/configuration_files
-configuration_basename test01.lua"
output="screen">
<remap from="scan" to="scan" />
</node>
<!-- cartographer_occupancy_grid_node -->
<node pkg="cartographer_ros" type="cartographer_occupancy_grid_node"
name="cartographer_occupancy_grid_node"
args="-resolution 0.05" />
<node pkg="joint_state_publisher" name="joint_state_publisher" type="joint_state_publisher" />
<node pkg="robot_state_publisher" name="robot_state_publisher" type="robot_state_publisher" />
<node name="rviz" pkg="rviz" type="rviz" required="true"
args="-d $(find cartographer_ros)/configuration_files/carto_test01.rviz" />
</launch>
launch文件的含义是:
- 由于是仿真,所以设置/use_sim_time为true
- 启动cartographer,注意这里的.lua文件,每个.launch都对应一个.lua文件
configuration_directory
和configuration_basename
是命令行需要传递的参数的关键字,使用Google gflags可以大大简化命令行参数处理,意思就是,roslaunch文件中的内容会赋值给程序,显然赋值到程序中的是两个代表路径和文件名字的字符串$(find cartographer_ros)/configuration_files和backpack_2d.lua,得到赋值的变量名字会写成FLAGS_configuration_directory和FLAGS_configuration_basename- remap话题重映射,因为在Cartographer源码中,其订阅的话题为points2、scan、odom,所以要转换成你的传感器发布的话题名称,所以要重新建立一个映射关系。
- 启动cartographer的建图节点,
-resolution
和上面一样,代表地图分辨率,在函数cartographer_ros/occupancy_grid_node_main.cc
中处理 - 启动rviz,并通过required="true"设置rviz为必要节点,rviz挂了其他节点也会被终止。-d的含义是运行指定的.rviz文件
lua文件:
/home/lxy/carto_ws/cartographer_detailed_comments_ws/src/cartographer_ros/cartographer_ros/configuration_files/test01.lua
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
-- 跟踪和发布的frame都改成雷达的frameID
tracking_frame = "base_footprint",
published_frame = "base_footprint",
odom_frame = "odom",
-- true改为false,不用提供里程计数据
provide_odom_frame = false,
-- false改为true,仅发布2D位资
publish_frame_projected_to_2d = true,
use_pose_extrapolator = true,
-- true改为false,不使用里程计数据
use_odometry = false,
use_nav_sat = false,
use_landmarks = false,
-- 0改为1,使用一个雷达
num_laser_scans = 1,
-- 1改为0,不使用多波雷达
num_multi_echo_laser_scans = 0,
-- 10改为1,1/1=1等于不分割
num_subdivisions_per_laser_scan = 1,
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.,
}
-- false改为true,启动2D SLAM
MAP_BUILDER.use_trajectory_builder_2d = true
-- 0改成0.10,比机器人半径小的都忽略
TRAJECTORY_BUILDER_2D.min_range = 0.10
-- 30改成3.5,限制在雷达最大扫描范围内,越小一般越精确些
TRAJECTORY_BUILDER_2D.max_range = 5.5
-- 5改成3,传感器数据超出有效范围最大值
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 3.
-- true改成false,不使用IMU数据,大家可以开启,然后对比下效果
TRAJECTORY_BUILDER_2D.use_imu_data = false
-- false改成true,使用实时回环检测来进行前端的扫描匹配
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
-- 1.0改成0.1,提高对运动的敏感度
-- TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.1)
-- 0.55改成0.65,Fast csm的最低分数,高于此分数才进行优化。
POSE_GRAPH.constraint_builder.min_score = 0.65
--0.6改成0.7,全局定位最小分数,低于此分数则认为目前全局定位不准确
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.7
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1
POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
-- 设置0可关闭全局SLAM
-- POSE_GRAPH.optimize_every_n_nodes = 0
return options
我的tf树如下,没有imu,发布tf的最上层坐标系为base_footprint.所以我这里将跟踪和发布的frame都改写为 base_footprint,使用单线激光雷达。
结语:
首先大致讲解了在有bag包的情况下去配置launch和lua文件,而我这里实现了在仿真环境下如何去配置这个launch和lua文件,另外需要注意的就是,修改.launch与.lua文件之后,需要重新编译。