12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061 |
- -- 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 = "laser",
- published_frame = "laser",
- odom_frame = "odom",
- provide_odom_frame = false,
- publish_frame_projected_to_2d = false,
- use_pose_extrapolator = true,
- use_odometry = false,
- use_nav_sat = false,
- use_landmarks = false,
- 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 = 3e-2,
- trajectory_publish_period_sec = 3e-2,
- rangefinder_sampling_ratio = 1.,
- odometry_sampling_ratio = 1.,
- fixed_frame_pose_sampling_ratio = 1.,
- imu_sampling_ratio = 1.,
- landmarks_sampling_ratio = 1.,
- }
- MAP_BUILDER.num_background_threads=6
- 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.)
- POSE_GRAPH.optimization_problem.huber_scale = 1e2
- TRAJECTORY_BUILDER.pure_localization_trimmer = {
- max_submaps_to_keep = 3,
- }
- POSE_GRAPH.optimize_every_n_nodes = 10
- return options
|