1 -- Copyright 2016 The Cartographer Authors
3 -- Licensed under the Apache License, Version 2.0 (the "License");
4 -- you may not use this file except in compliance with the License.
5 -- You may obtain a copy of the License at
7 -- http://www.apache.org/licenses/LICENSE-2.0
9 -- Unless required by applicable law or agreed to in writing, software
10 -- distributed under the License is distributed on an "AS IS" BASIS,
11 -- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 -- See the License for the specific language governing permissions and
13 -- limitations under the License.
15 include "map_builder.lua"
18 map_builder = MAP_BUILDER,
20 tracking_frame = "base_imu_link",
21 published_frame = "base_link",
23 provide_odom_frame = false,
25 use_laser_scan = true,
26 use_multi_echo_laser_scan = false,
28 lookup_transform_timeout_sec = 0.2,
29 submap_publish_period_sec = 0.3,
30 pose_publish_period_sec = 5e-3,
33 MAP_BUILDER.use_trajectory_builder_2d = true
35 TRAJECTORY_BUILDER_2D.laser_min_range = 0.4
36 TRAJECTORY_BUILDER_2D.laser_max_range = 3.5
37 TRAJECTORY_BUILDER_2D.laser_missing_echo_ray_length = 2.0
38 TRAJECTORY_BUILDER_2D.use_imu_data = true
39 TRAJECTORY_BUILDER_2D.motion_filter.max_time_seconds = 0.3
40 TRAJECTORY_BUILDER_2D.motion_filter.max_distance_meters = 0.2
41 TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(3.)
42 TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 70
43 TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 300
45 TRAJECTORY_BUILDER_2D.submaps.resolution = 0.035
46 TRAJECTORY_BUILDER_2D.submaps.num_laser_fans = 120
47 SPARSE_POSE_GRAPH.optimize_every_n_scans = 120
48 SPARSE_POSE_GRAPH.constraint_builder.min_score = 0.82
49 SPARSE_POSE_GRAPH.constraint_builder.sampling_ratio = 1.
50 SPARSE_POSE_GRAPH.constraint_builder.ceres_scan_matcher.covariance_scale = 3e-5