- 首先根據官方指導安裝
cartographer
。 - 然后創建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
- 現在需要安裝
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
- 最后編譯
cd carto_wscatkin_make
- 然后就可以使用了
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的framepublished_frame = "base_link", -- 定位結果發布到tf樹: map_frame -> published_frameodom_frame = "odom", -- 里程計的坐標系名字-- 是否提供odom的tf, 如果為true,則tf樹為map_frame->odom_frame->published_frame;如果為false tf樹為map_frame->published_frameprovide_odom_frame = false, --包含的cartographer里的lua文件publish_frame_projected_to_2d = true, -- 是否將坐標系投影到平面上,沒啥用use_odometry = false, -- 是否使用里程計,如果使用要求一定要有odom的tf use_nav_sat = false,use_landmarks = false, -- 是否使用landmarknum_laser_scans = 1, -- 單線激光掃描數據的話題數量num_multi_echo_laser_scans = 0,num_subdivisions_per_laser_scan = 1, -- 一幀數據被分成幾次處理,一般為1num_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-1POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
POSE_GRAPH.constraint_builder.min_score = 0.65return options