cartographer_ros使用

  1. 首先根据官方指导安装cartographer
  2. 然后创建ros工作空间并拉取 cartographer_ros 代码
mkdir -p carto_ws/src
cd carto_ws/src
catkin_init_workspace 
git clone https://github.com/cartographer-project/cartographer_ros.git
  1. 现在需要安装cartographer_ros依赖项。首先,我们使用rosdep来安装所需的软件包。如果在安装ROS之后已经执行了sudo rosdep init命令,那么它将打印一个错误。此错误可以忽略。无法翻墙可以安装rosdepc,使用国内源只需将rosdep替换为rosdepc
sudo rosdep init
rosdep update
rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y
  1. 最后编译
 cd carto_ws
 catkin_make
  1. 然后就可以使用了
source devel setup.bash
roslaunch package_name carto.launch

launch文件:

<launch>
    <param name="/use_sim_time" value="true" /> <!--仿真就设为true,实物就设为false-->
    <node name="cartographer_node" pkg="cartographer_ros" type="cartographer_node" args="
    -configuration_directory $(find limo_bringup)/param
    -configuration_basename build_map_2d.lua">
        <remap from="scan" to="limo/scan" /> <!--重映射为实际的LaserScan话题-->
        <remap from="imu" to="limo/imu" /> <!--重映射为实际的IMU话题-->
    </node>
    <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros" type="cartographer_occupancy_grid_node" args="-resolution 0.05" /> <!--resolution为地图网格大小,越大速度越快,越小精度越好-->
    <node name="rviz" pkg="rviz" type="rviz" required="true" args="-d $(find limo_bringup)/rviz/cartographer.rviz" />
</launch>

cartographer 参数设置

cartographer可以工作在两种模式:有IMU和没有IMU,以下为cartographer的lua参数文件:

--包含的cartographer里的lua文件
include "map_builder.lua" 
include "trajectory_builder.lua"

options = {
  map_builder = MAP_BUILDER, -- map_builder.lua的配置信息
  trajectory_builder = TRAJECTORY_BUILDER, -- trajectory_builder.lua的配置信息
  map_frame = "map", -- 地图坐标系的名字
  tracking_frame = "imu_link",  -- 将所有传感器数据转换到这个坐标系下,一般设置为频率最高的传感器的frame,如果有IMU就是IMU的frame,如果没有就是laser的frame
  published_frame = "base_link", -- 定位结果发布到tf树: map_frame -> published_frame
  odom_frame = "odom", -- 里程计的坐标系名字
  -- 是否提供odom的tf, 如果为true,则tf树为map_frame->odom_frame->published_frame;如果为false tf树为map_frame->published_frame
  provide_odom_frame = false, --包含的cartographer里的lua文件
  publish_frame_projected_to_2d = true, -- 是否将坐标系投影到平面上,没啥用
  use_odometry = false, -- 是否使用里程计,如果使用要求一定要有odom的tf 
  use_nav_sat = false,
  use_landmarks = false, -- 是否使用landmark
  num_laser_scans = 1, -- 单线激光扫描数据的话题数量
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 1, -- 一帧数据被分成几次处理,一般为1
  num_point_clouds = 0, -- PointCloud2点云数据的话题数量
  lookup_transform_timeout_sec = 0.2, -- 查找tf时的超时等待时间
  submap_publish_period_sec = 0.3, -- submap发布的时间间隔
  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., -- IMU数据的降采样比例
  landmarks_sampling_ratio = 1., -- landmarks的降采样比例
}

MAP_BUILDER.use_trajectory_builder_2d = true -- 使用2d slam算法,2d和3d一定要有一个为true,且只能有一个

TRAJECTORY_BUILDER_2D.submaps.num_range_data = 35
TRAJECTORY_BUILDER_2D.min_range = 0.5
TRAJECTORY_BUILDER_2D.max_range = 20
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 1.

TRAJECTORY_BUILDER_2D.use_imu_data = true -- 是否使用IMU数据
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
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
-- 提高精度主要修改的参数,设置成比较小的值
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 1e-1
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 4e-1

POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
POSE_GRAPH.constraint_builder.min_score = 0.65

return options

运行效果如下:

cartographer

  • 7
    点赞
  • 14
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

Shilong Wang

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值