45 lines
1.5 KiB
Lua
45 lines
1.5 KiB
Lua
-- Copyright 2016 The Cartographer Authors
|
|
--
|
|
-- Licensed under the Apache License, Version 2.0 (the "License");
|
|
-- you may not use this file except in compliance with the License.
|
|
-- You may obtain a copy of the License at
|
|
--
|
|
-- http://www.apache.org/licenses/LICENSE-2.0
|
|
--
|
|
-- Unless required by applicable law or agreed to in writing, software
|
|
-- distributed under the License is distributed on an "AS IS" BASIS,
|
|
-- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
|
-- See the License for the specific language governing permissions and
|
|
-- limitations under the License.
|
|
|
|
include "map_builder.lua"
|
|
include "trajectory_builder.lua"
|
|
|
|
options = {
|
|
map_builder = MAP_BUILDER,
|
|
trajectory_builder = TRAJECTORY_BUILDER,
|
|
map_frame = "map",
|
|
tracking_frame = "base_footprint",
|
|
published_frame = "base_footprint",
|
|
odom_frame = "odom",
|
|
provide_odom_frame = true,
|
|
use_odometry = false,
|
|
use_laser_scan = true,
|
|
use_multi_echo_laser_scan = false,
|
|
num_point_clouds = 0,
|
|
lookup_transform_timeout_sec = 0.2,
|
|
submap_publish_period_sec = 0.3,
|
|
pose_publish_period_sec = 5e-3,
|
|
}
|
|
|
|
MAP_BUILDER.use_trajectory_builder_2d = true
|
|
|
|
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
|
|
TRAJECTORY_BUILDER_2D.use_imu_data = false
|
|
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.15
|
|
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.angular_search_window = math.rad(35.)
|
|
|
|
SPARSE_POSE_GRAPH.optimization_problem.huber_scale = 1e2
|
|
|
|
return options
|