configuration.rst 5.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134
  1. .. Copyright 2016 The Cartographer Authors
  2. .. Licensed under the Apache License, Version 2.0 (the "License");
  3. you may not use this file except in compliance with the License.
  4. You may obtain a copy of the License at
  5. .. http://www.apache.org/licenses/LICENSE-2.0
  6. .. Unless required by applicable law or agreed to in writing, software
  7. distributed under the License is distributed on an "AS IS" BASIS,
  8. WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
  9. See the License for the specific language governing permissions and
  10. limitations under the License.
  11. =========================================
  12. Lua configuration reference documentation
  13. =========================================
  14. Note that Cartographer's ROS integration uses `tf2`_, thus all frame IDs are
  15. expected to contain only a frame name (lower-case with underscores) and no
  16. prefix or slashes. See `REP 105`_ for commonly used coordinate frames.
  17. Note that topic names are given as *base* names (see `ROS Names`_) in
  18. Cartographer's ROS integration. This means it is up to the user of the
  19. Cartographer node to remap, or put them into a namespace.
  20. The following are Cartographer's ROS integration top-level options, all of which
  21. must be specified in the Lua configuration file:
  22. map_frame
  23. The ROS frame ID to use for publishing submaps, the parent frame of poses,
  24. usually "map".
  25. tracking_frame
  26. The ROS frame ID of the frame that is tracked by the SLAM algorithm. If an IMU
  27. is used, it should be at its position, although it might be rotated. A common
  28. choice is "imu_link".
  29. published_frame
  30. The ROS frame ID to use as the child frame for publishing poses. For example
  31. "odom" if an "odom" frame is supplied by a different part of the system. In
  32. this case the pose of "odom" in the *map_frame* will be published. Otherwise,
  33. setting it to "base_link" is likely appropriate.
  34. odom_frame
  35. Only used if *provide_odom_frame* is true. The frame between *published_frame*
  36. and *map_frame* to be used for publishing the (non-loop-closed) local SLAM
  37. result. Usually "odom".
  38. provide_odom_frame
  39. If enabled, the local, non-loop-closed, continuous pose will be published as
  40. the *odom_frame* in the *map_frame*.
  41. publish_frame_projected_to_2d
  42. If enabled, the published pose will be restricted to a pure 2D pose (no roll,
  43. pitch, or z-offset). This prevents potentially unwanted out-of-plane poses in
  44. 2D mode that can occur due to the pose extrapolation step (e.g. if the pose
  45. shall be published as a 'base-footprint'-like frame)
  46. use_odometry
  47. If enabled, subscribes to `nav_msgs/Odometry`_ on the topic "odom". Odometry
  48. must be provided in this case, and the information will be included in SLAM.
  49. use_nav_sat
  50. If enabled, subscribes to `sensor_msgs/NavSatFix`_ on the topic "fix".
  51. Navigation data must be provided in this case, and the information will be
  52. included in the global SLAM.
  53. use_landmarks
  54. If enabled, subscribes to `cartographer_ros_msgs/LandmarkList`_ on the topic
  55. "landmarks". Landmarks must be provided in this case, and the information
  56. will be included in SLAM.
  57. num_laser_scans
  58. Number of laser scan topics to subscribe to. Subscribes to
  59. `sensor_msgs/LaserScan`_ on the "scan" topic for one laser scanner, or topics
  60. "scan_1", "scan_2", etc. for multiple laser scanners.
  61. num_multi_echo_laser_scans
  62. Number of multi-echo laser scan topics to subscribe to. Subscribes to
  63. `sensor_msgs/MultiEchoLaserScan`_ on the "echoes" topic for one laser scanner,
  64. or topics "echoes_1", "echoes_2", etc. for multiple laser scanners.
  65. num_subdivisions_per_laser_scan
  66. Number of point clouds to split each received (multi-echo) laser scan into.
  67. Subdividing a scan makes it possible to unwarp scans acquired while the
  68. scanners are moving. There is a corresponding trajectory builder option to
  69. accumulate the subdivided scans into a point cloud that will be used for scan
  70. matching.
  71. num_point_clouds
  72. Number of point cloud topics to subscribe to. Subscribes to
  73. `sensor_msgs/PointCloud2`_ on the "points2" topic for one rangefinder, or
  74. topics "points2_1", "points2_2", etc. for multiple rangefinders.
  75. lookup_transform_timeout_sec
  76. Timeout in seconds to use for looking up transforms using `tf2`_.
  77. submap_publish_period_sec
  78. Interval in seconds at which to publish the submap poses, e.g. 0.3 seconds.
  79. pose_publish_period_sec
  80. Interval in seconds at which to publish poses, e.g. 5e-3 for a frequency of
  81. 200 Hz.
  82. trajectory_publish_period_sec
  83. Interval in seconds at which to publish the trajectory markers, e.g. 30e-3
  84. for 30 milliseconds.
  85. rangefinder_sampling_ratio
  86. Fixed ratio sampling for range finders messages.
  87. odometry_sampling_ratio
  88. Fixed ratio sampling for odometry messages.
  89. fixed_frame_sampling_ratio
  90. Fixed ratio sampling for fixed frame messages.
  91. imu_sampling_ratio
  92. Fixed ratio sampling for IMU messages.
  93. landmarks_sampling_ratio
  94. Fixed ratio sampling for landmarks messages.
  95. .. _REP 105: http://www.ros.org/reps/rep-0105.html
  96. .. _ROS Names: http://wiki.ros.org/Names
  97. .. _nav_msgs/OccupancyGrid: http://docs.ros.org/api/nav_msgs/html/msg/OccupancyGrid.html
  98. .. _nav_msgs/Odometry: http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html
  99. .. _sensor_msgs/LaserScan: http://docs.ros.org/api/sensor_msgs/html/msg/LaserScan.html
  100. .. _sensor_msgs/MultiEchoLaserScan: http://docs.ros.org/api/sensor_msgs/html/msg/MultiEchoLaserScan.html
  101. .. _sensor_msgs/PointCloud2: http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html
  102. .. _sensor_msgs/NavSatFix: http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html
  103. .. _cartographer_ros_msgs/LandmarkList: https://github.com/googlecartographer/cartographer_ros/blob/4b39ee68c7a4d518bf8d01a509331e2bc1f514a0/cartographer_ros_msgs/msg/LandmarkList.msg
  104. .. _tf2: http://wiki.ros.org/tf2