demo_sick_location.lua 2.0 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061
  1. -- Copyright 2016 The Cartographer Authors
  2. --
  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
  6. --
  7. -- http://www.apache.org/licenses/LICENSE-2.0
  8. --
  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.
  14. include "map_builder.lua"
  15. include "trajectory_builder.lua"
  16. options = {
  17. map_builder = MAP_BUILDER,
  18. trajectory_builder = TRAJECTORY_BUILDER,
  19. map_frame = "map",
  20. tracking_frame = "laser",
  21. published_frame = "laser",
  22. odom_frame = "odom",
  23. provide_odom_frame = false,
  24. publish_frame_projected_to_2d = false,
  25. use_pose_extrapolator = true,
  26. use_odometry = false,
  27. use_nav_sat = false,
  28. use_landmarks = false,
  29. num_laser_scans = 1,
  30. num_multi_echo_laser_scans = 0,
  31. num_subdivisions_per_laser_scan = 1,
  32. num_point_clouds = 0,
  33. lookup_transform_timeout_sec = 0.2,
  34. submap_publish_period_sec = 0.3,
  35. pose_publish_period_sec = 3e-2,
  36. trajectory_publish_period_sec = 3e-2,
  37. rangefinder_sampling_ratio = 1.,
  38. odometry_sampling_ratio = 1.,
  39. fixed_frame_pose_sampling_ratio = 1.,
  40. imu_sampling_ratio = 1.,
  41. landmarks_sampling_ratio = 1.,
  42. }
  43. MAP_BUILDER.num_background_threads=6
  44. MAP_BUILDER.use_trajectory_builder_2d = true
  45. TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
  46. TRAJECTORY_BUILDER_2D.use_imu_data = false
  47. TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.15
  48. TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.angular_search_window = math.rad(35.)
  49. POSE_GRAPH.optimization_problem.huber_scale = 1e2
  50. TRAJECTORY_BUILDER.pure_localization_trimmer = {
  51. max_submaps_to_keep = 3,
  52. }
  53. POSE_GRAPH.optimize_every_n_nodes = 10
  54. return options