demo_sick.lua 1.3 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243
  1. include "map_builder.lua"
  2. include "trajectory_builder.lua"
  3. options = {
  4. map_builder = MAP_BUILDER,
  5. trajectory_builder = TRAJECTORY_BUILDER,
  6. map_frame = "map",
  7. tracking_frame = "laser",
  8. published_frame = "laser",
  9. odom_frame = "odom",
  10. provide_odom_frame = false,
  11. publish_frame_projected_to_2d = false,
  12. use_pose_extrapolator = true,
  13. use_odometry = false,
  14. use_nav_sat = false,
  15. use_landmarks = false,
  16. num_laser_scans = 1,
  17. num_multi_echo_laser_scans = 0,
  18. num_subdivisions_per_laser_scan = 1,
  19. num_point_clouds = 0,
  20. lookup_transform_timeout_sec = 0.2,
  21. submap_publish_period_sec = 0.3,
  22. pose_publish_period_sec = 3e-2,
  23. trajectory_publish_period_sec = 3e-2,
  24. rangefinder_sampling_ratio = 1.,
  25. odometry_sampling_ratio = 1.,
  26. fixed_frame_pose_sampling_ratio = 1.,
  27. imu_sampling_ratio = 1.,
  28. landmarks_sampling_ratio = 1.,
  29. }
  30. MAP_BUILDER.num_background_threads=6
  31. MAP_BUILDER.use_trajectory_builder_2d = true
  32. TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
  33. TRAJECTORY_BUILDER_2D.use_imu_data = false
  34. TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.15
  35. TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.angular_search_window = math.rad(35.)
  36. POSE_GRAPH.optimization_problem.huber_scale = 1e2
  37. return options