44 lines
1.3 KiB
Lua
44 lines
1.3 KiB
Lua
|
include "map_builder.lua"
|
||
|
include "trajectory_builder.lua"
|
||
|
|
||
|
options = {
|
||
|
map_builder = MAP_BUILDER,
|
||
|
trajectory_builder = TRAJECTORY_BUILDER,
|
||
|
map_frame = "map",
|
||
|
tracking_frame = "base",
|
||
|
published_frame = "odom",
|
||
|
odom_frame = "odom",
|
||
|
provide_odom_frame = false,
|
||
|
publish_frame_projected_to_2d = false,
|
||
|
use_odometry = true,
|
||
|
use_nav_sat = false,
|
||
|
use_landmarks = false,
|
||
|
num_laser_scans = 0,
|
||
|
num_multi_echo_laser_scans = 0,
|
||
|
num_subdivisions_per_laser_scan = 1,
|
||
|
num_point_clouds = 1,
|
||
|
lookup_transform_timeout_sec = 0.1,
|
||
|
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 = 0.5,
|
||
|
fixed_frame_pose_sampling_ratio = 0.9,
|
||
|
imu_sampling_ratio = 1.,
|
||
|
landmarks_sampling_ratio = 1.,
|
||
|
}
|
||
|
TRAJECTORY_BUILDER_3D.num_accumulated_range_data = 160
|
||
|
|
||
|
TRAJECTORY_BUILDER_3D.num_accumulated_range_data = 1
|
||
|
|
||
|
MAP_BUILDER.use_trajectory_builder_3d = true
|
||
|
MAP_BUILDER.num_background_threads = 7
|
||
|
|
||
|
POSE_GRAPH.optimization_problem.huber_scale = 5e2
|
||
|
POSE_GRAPH.optimize_every_n_nodes = 100
|
||
|
POSE_GRAPH.constraint_builder.sampling_ratio = 0.03
|
||
|
POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10
|
||
|
POSE_GRAPH.constraint_builder.min_score = 0.62
|
||
|
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.66
|
||
|
|
||
|
return options
|