一、前期工作
1.IMU型号是xsens Mti 300的,激光雷达是hokuyo的。
下载驱动包,以及调试在前面博客。
2.安装cartographer程序包
二、文件修改
在cartographer_ros/configuration_files文件夹下新建Imu_hokuyo.lua,Imu_hokuyo.rviz,Imu_hokuyo_model.urdf文件。
1.Imu_hokuyo.lua
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER,
trajectory_builder = TRAJECTORY_BUILDER,
map_frame = "map",
tracking_frame = "imu",
published_frame = "laser",
odom_frame = "odom",
provide_odom_frame = true, --算法内提供里程计
--provide_odom_frame = false, --算法内提供里程计
publish_frame_projected_to_2d = false,
use_odometry = false, --不使用里程计
use_nav_sat = false,
use_landmarks = false,
--use_pose_extrapolator = true,
num_laser_scans = 1,
num_multi_echo_laser_scans = 0,
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.,
}
MAP_BUILDER.use_trajectory_builder_2d = true
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 35
TRAJECTORY_BUILDER_2D.min_range = 2
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
POSE_GRAPH.optimization_problem.huber_scale = 1e2
POSE_GRAPH.optimize_every_n_nodes = 35
POSE_GRAPH.constraint_builder.min_score = 0.65
return options
其中需要注注意
tracking_frame = "imu", --跟踪帧,这里选择/imu话题里面的frame_id
published_frame = "laser", 激光/scan话题里面的frame_id
TRAJECTORY_BUILDER_2D.use_imu_data = true --打开订阅Imu话题
这两个传感器的frame_id都可以在xsens_driver.launch和hokuyo_laser.launch里面修改。
如果默认的frame_id是/imu或者/laser,则需要把“/”去掉,改为imu和laser,否则cartographer会报错。
2.Imu_hokuyo.rviz(这个就是默认的demo_2d.rviz)
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Submaps1
- /PointCloud21
Splitter Ratio: 0.600671