ros_api.rst 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235
  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. ROS API reference documentation
  13. ===============================
  14. .. image:: nodes_graph_demo_2d.jpg
  15. Cartographer Node
  16. =================
  17. The `cartographer_node`_ is the SLAM node used for online, real-time SLAM.
  18. .. _cartographer_node: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros/cartographer_ros/node_main.cc
  19. Command-line Flags
  20. ------------------
  21. Call the node with the ``--help`` flag to see all available options.
  22. Subscribed Topics
  23. -----------------
  24. The following range data topics are mutually exclusive. At least one source of
  25. range data is required.
  26. scan (`sensor_msgs/LaserScan`_)
  27. Supported in 2D and 3D (e.g. using an axially rotating planar laser scanner).
  28. If *num_laser_scans* is set to 1 in the :doc:`configuration`, this topic will
  29. be used as input for SLAM. If *num_laser_scans* is greater than 1, multiple
  30. numbered scan topics (i.e. scan_1, scan_2, scan_3, ... up to and including
  31. *num_laser_scans*) will be used as inputs for SLAM.
  32. echoes (`sensor_msgs/MultiEchoLaserScan`_)
  33. Supported in 2D and 3D (e.g. using an axially rotating planar laser scanner).
  34. If *num_multi_echo_laser_scans* is set to 1 in the :doc:`configuration`, this
  35. topic will be used as input for SLAM. Only the first echo is used. If
  36. *num_multi_echo_laser_scans* is greater than 1, multiple numbered echoes
  37. topics (i.e. echoes_1, echoes_2, echoes_3, ... up to and including
  38. *num_multi_echo_laser_scans*) will be used as inputs for SLAM.
  39. points2 (`sensor_msgs/PointCloud2`_)
  40. If *num_point_clouds* is set to 1 in the :doc:`configuration`, this topic will
  41. be used as input for SLAM. If *num_point_clouds* is greater than 1, multiple
  42. numbered points2 topics (i.e. points2_1, points2_2, points2_3, ... up to and
  43. including *num_point_clouds*) will be used as inputs for SLAM.
  44. The following additional sensor data topics may also be provided:
  45. imu (`sensor_msgs/Imu`_)
  46. Supported in 2D (optional) and 3D (required). This topic will be used as
  47. input for SLAM.
  48. odom (`nav_msgs/Odometry`_)
  49. Supported in 2D (optional) and 3D (optional). If *use_odometry* is
  50. enabled in the :doc:`configuration`, this topic will be used as input for
  51. SLAM.
  52. .. TODO: add NavSatFix? Landmarks?
  53. Published Topics
  54. ----------------
  55. scan_matched_points2 (`sensor_msgs/PointCloud2`_)
  56. Point cloud as it was used for the purpose of scan-to-submap matching. This
  57. cloud may be both filtered and projected depending on the
  58. :doc:`configuration`.
  59. submap_list (`cartographer_ros_msgs/SubmapList`_)
  60. List of all submaps, including the pose and latest version number of each
  61. submap, across all trajectories.
  62. tracked_pose (`geometry_msgs/PoseStamped`_)
  63. Only published if the parameter ``publish_tracked_pose`` is set to ``true``.
  64. The pose of the tracked frame with respect to the map frame.
  65. Services
  66. --------
  67. All services responses include also a ``StatusResponse`` that comprises a ``code`` and a ``message`` field.
  68. For consistency, the integer ``code`` is equivalent to the status codes used in the `gRPC`_ API.
  69. .. _gRPC: https://developers.google.com/maps-booking/reference/grpc-api/status_codes
  70. submap_query (`cartographer_ros_msgs/SubmapQuery`_)
  71. Fetches the requested submap.
  72. start_trajectory (`cartographer_ros_msgs/StartTrajectory`_)
  73. Starts a trajectory using default sensor topics and the provided configuration.
  74. An initial pose can be optionally specified. Returns an assigned trajectory ID.
  75. trajectory_query (`cartographer_ros_msgs/TrajectoryQuery`_)
  76. Returns the trajectory data from the pose graph.
  77. finish_trajectory (`cartographer_ros_msgs/FinishTrajectory`_)
  78. Finishes the given `trajectory_id`'s trajectory by running a final optimization.
  79. write_state (`cartographer_ros_msgs/WriteState`_)
  80. Writes the current internal state to disk into `filename`. The file will
  81. usually end up in `~/.ros` or `ROS_HOME` if it is set. This file can be used
  82. as input to the `assets_writer_main` to generate assets like probability
  83. grids, X-Rays or PLY files.
  84. get_trajectory_states (`cartographer_ros_msgs/GetTrajectoryStates`_)
  85. Returns the IDs and the states of the trajectories.
  86. For example, this can be useful to observe the state of Cartographer from a separate node.
  87. read_metrics (`cartographer_ros_msgs/ReadMetrics`_)
  88. Returns the latest values of all internal metrics of Cartographer.
  89. The collection of runtime metrics is optional and has to be activated with the ``--collect_metrics`` command line flag in the node.
  90. Required tf Transforms
  91. ----------------------
  92. .. image:: frames_demo_2d.jpg
  93. Transforms from all incoming sensor data frames to the :doc:`configured
  94. <configuration>` *tracking_frame* and *published_frame* must be available.
  95. Typically, these are published periodically by a `robot_state_publisher` or a
  96. `static_transform_publisher`.
  97. Provided tf Transforms
  98. ----------------------
  99. The transformation between the :doc:`configured <configuration>` *map_frame*
  100. and *published_frame* is provided unless the parameter ``publish_to_tf`` is set to ``false``.
  101. If *provide_odom_frame* is enabled in the :doc:`configuration`, additionally a continuous
  102. (i.e. unaffected by loop closure) transform between the :doc:`configured
  103. <configuration>` *odom_frame* and *published_frame* will be provided.
  104. .. _robot_state_publisher: http://wiki.ros.org/robot_state_publisher
  105. .. _static_transform_publisher: http://wiki.ros.org/tf#static_transform_publisher
  106. .. _cartographer_ros_msgs/FinishTrajectory: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros_msgs/srv/FinishTrajectory.srv
  107. .. _cartographer_ros_msgs/SubmapList: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros_msgs/msg/SubmapList.msg
  108. .. _cartographer_ros_msgs/SubmapQuery: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros_msgs/srv/SubmapQuery.srv
  109. .. _cartographer_ros_msgs/StartTrajectory: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros_msgs/srv/StartTrajectory.srv
  110. .. _cartographer_ros_msgs/TrajectoryQuery: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros_msgs/srv/TrajectoryQuery.srv
  111. .. _cartographer_ros_msgs/WriteState: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros_msgs/srv/WriteState.srv
  112. .. _cartographer_ros_msgs/GetTrajectoryStates: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros_msgs/srv/GetTrajectoryStates.srv
  113. .. _cartographer_ros_msgs/ReadMetrics: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros_msgs/srv/ReadMetrics.srv
  114. .. _geometry_msgs/PoseStamped: http://docs.ros.org/api/geometry_msgs/html/msg/PoseStamped.html
  115. .. _nav_msgs/OccupancyGrid: http://docs.ros.org/api/nav_msgs/html/msg/OccupancyGrid.html
  116. .. _nav_msgs/Odometry: http://docs.ros.org/api/nav_msgs/html/msg/Odometry.html
  117. .. _sensor_msgs/Imu: http://docs.ros.org/api/sensor_msgs/html/msg/Imu.html
  118. .. _sensor_msgs/LaserScan: http://docs.ros.org/api/sensor_msgs/html/msg/LaserScan.html
  119. .. _sensor_msgs/MultiEchoLaserScan: http://docs.ros.org/api/sensor_msgs/html/msg/MultiEchoLaserScan.html
  120. .. _sensor_msgs/PointCloud2: http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html
  121. Offline Node
  122. ============
  123. The `offline_node`_ is the fastest way of SLAMing a bag of sensor data.
  124. It does not listen on any topics, instead it reads TF and sensor data out of a set of bags provided on the commandline.
  125. It also publishes a clock with the advancing sensor data, i.e. replaces ``rosbag play``.
  126. In all other regards, it behaves like the ``cartographer_node``.
  127. Each bag will become a separate trajectory in the final state.
  128. Once it is done processing all data, it writes out the final Cartographer state and exits.
  129. .. _offline_node: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros/cartographer_ros/offline_node_main.cc
  130. Published Topics
  131. ----------------
  132. In addition to the topics that are published by the online node, this node also publishes:
  133. ~bagfile_progress (`cartographer_ros_msgs/BagfileProgress`_)
  134. Bag files processing progress including detailed information about the bag currently being processed which will be published with a predefined
  135. interval that can be specified using ``~bagfile_progress_pub_interval`` ROS parameter.
  136. .. _cartographer_ros_msgs/BagfileProgress: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros_msgs/msg/BagfileProgress.msg
  137. Parameters
  138. ----------
  139. ~bagfile_progress_pub_interval (double, default=10.0):
  140. The interval of publishing bag files processing progress in seconds.
  141. Occupancy grid Node
  142. ===================
  143. The `occupancy_grid_node`_ listens to the submaps published by SLAM, builds an ROS occupancy_grid out of them and publishes it.
  144. This tool is useful to keep old nodes that require a single monolithic map to work happy until new nav stacks can deal with Cartographer's submaps directly.
  145. Generating the map is expensive and slow, so map updates are in the order of seconds.
  146. You can can selectively include/exclude submaps from frozen (static) or active trajectories with a command line option.
  147. Call the node with the ``--help`` flag to see these options.
  148. .. _occupancy_grid_node: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros/cartographer_ros/occupancy_grid_node_main.cc
  149. Subscribed Topics
  150. -----------------
  151. It subscribes to Cartographer's ``submap_list`` topic only.
  152. Published Topics
  153. ----------------
  154. map (`nav_msgs/OccupancyGrid`_)
  155. If subscribed to, the node will continuously compute and publish the map. The
  156. time between updates will increase with the size of the map. For faster
  157. updates, use the submaps APIs.
  158. Pbstream Map Publisher Node
  159. ===========================
  160. The `pbstream_map_publisher`_ is a simple node that creates a static occupancy grid out of a serialized Cartographer state (pbstream format).
  161. It is an efficient alternative to the occupancy grid node if live updates are not important.
  162. .. _pbstream_map_publisher: https://github.com/cartographer-project/cartographer_ros/blob/master/cartographer_ros/cartographer_ros/pbstream_map_publisher_main.cc
  163. Subscribed Topics
  164. -----------------
  165. None.
  166. Published Topics
  167. ----------------
  168. map (`nav_msgs/OccupancyGrid`_)
  169. The published occupancy grid topic is latched.