Rework the documentation as a step-by-step guide (#952)
This restructures the doc as a tutorial leading newcomers to becoming experimented users. It adds pages on: - how to get started with Cartographer on a new .bag - how Cartographer works and can be tuned step-by-step - how to use "extra" features of Cartographer - how to contribute to Cartographer It also provides some cosmethic changes with: new titles, non-indented code blocks, various illustrations, reworked paragraphs for clarity...master
parent
b0420bf430
commit
ba33291392
|
@ -0,0 +1,366 @@
|
||||||
|
.. Copyright 2018 The Cartographer Authors
|
||||||
|
|
||||||
|
.. Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
you may not use this file except in compliance with the License.
|
||||||
|
You may obtain a copy of the License at
|
||||||
|
|
||||||
|
.. http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
|
||||||
|
.. Unless required by applicable law or agreed to in writing, software
|
||||||
|
distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
See the License for the specific language governing permissions and
|
||||||
|
limitations under the License.
|
||||||
|
|
||||||
|
Algorithm walkthrough for tuning
|
||||||
|
================================
|
||||||
|
|
||||||
|
Cartographer is a complex system and tuning it requires a good understanding of its inner working.
|
||||||
|
This page tries to give an intuitive overview of the different subsystems used by Cartographer along with their configuration values.
|
||||||
|
If you are interested in more than an introduction to Cartographer, you should refer to the Cartographer paper.
|
||||||
|
It only describes the 2D SLAM but it defines rigourously most of the concepts described here.
|
||||||
|
Those concepts generally apply to 3D as well.
|
||||||
|
|
||||||
|
W. Hess, D. Kohler, H. Rapp, and D. Andor,
|
||||||
|
`Real-Time Loop Closure in 2D LIDAR SLAM`_, in
|
||||||
|
*Robotics and Automation (ICRA), 2016 IEEE International Conference on*.
|
||||||
|
IEEE, 2016. pp. 1271–1278.
|
||||||
|
|
||||||
|
.. _Real-Time Loop Closure in 2D LIDAR SLAM: https://research.google.com/pubs/pub45466.html
|
||||||
|
|
||||||
|
Overview
|
||||||
|
--------
|
||||||
|
|
||||||
|
.. image:: https://raw.githubusercontent.com/googlecartographer/cartographer/master/docs/source/high_level_system_overview.png
|
||||||
|
:target: https://github.com/googlecartographer/cartographer/blob/master/docs/source/high_level_system_overview.png
|
||||||
|
|
||||||
|
Cartographer can be seen as two separate, but related subsystems.
|
||||||
|
The first one is **local SLAM** (sometimes also called **frontend** or local trajectory builder).
|
||||||
|
Its job is to build a succession of **submaps**.
|
||||||
|
Each submap is meant to be locally consistent but we accept that local SLAM drifts over time.
|
||||||
|
Most of the local SLAM options can be found in `install_isolated/share/cartographer/configuration_files/trajectory_builder_2d.lua`_ for 2D and `install_isolated/share/cartographer/configuration_files/trajectory_builder_3d.lua`_ for 3D. (for the rest of this page we will refer to `TRAJECTORY_BUILDER_nD` for the common options)
|
||||||
|
|
||||||
|
.. _install_isolated/share/cartographer/configuration_files/trajectory_builder_2d.lua: https://github.com/googlecartographer/cartographer/blob/df337194e21f98f8c7b0b88dab33f878066d4b56/configuration_files/trajectory_builder_2d.lua
|
||||||
|
.. _install_isolated/share/cartographer/configuration_files/trajectory_builder_3d.lua: https://github.com/googlecartographer/cartographer/blob/df337194e21f98f8c7b0b88dab33f878066d4b56/configuration_files/trajectory_builder_3d.lua
|
||||||
|
|
||||||
|
The other subsystem is **global SLAM** (sometimes called the **backend**).
|
||||||
|
It runs in background threads and its main job is to find **loop closure constraints**.
|
||||||
|
It does that by scan-matching **scans** (gathered in **nodes**) against submaps.
|
||||||
|
It also incorporates other sensor data to get a higher level view and identify the most consistent global solution.
|
||||||
|
In 3D, it also tries to find the direction of gravity.
|
||||||
|
Most of its options can be found in `install_isolated/share/cartographer/configuration_files/pose_graph.lua`_
|
||||||
|
|
||||||
|
.. _install_isolated/share/cartographer/configuration_files/pose_graph.lua: https://github.com/googlecartographer/cartographer/blob/df337194e21f98f8c7b0b88dab33f878066d4b56/configuration_files/pose_graph.lua
|
||||||
|
|
||||||
|
On a higher abstraction, the job of local SLAM is to generate good submaps and the job of global SLAM is to tie them most consistently together.
|
||||||
|
|
||||||
|
Input
|
||||||
|
-----
|
||||||
|
|
||||||
|
Range finding sensors (for example: LIDARs) provide depth information in multiple directions.
|
||||||
|
However, some of the measurements are irrelevant for SLAM.
|
||||||
|
If the sensor is partially covered with dust or if it is directed towards a part of the robot, some of the measured distance can be considered as noise for SLAM.
|
||||||
|
On the other hand, some of the furthest measurements can also come from undesired sources (reflection, sensor noise) and are irrelevant for SLAM as well.
|
||||||
|
To tackle those issue, Cartographer starts by applying a bandpass filter and only keeps range values between a certain min and max range.
|
||||||
|
Those min and max values should be chosen according to the specifications of your robot and sensors.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_nD.min_range
|
||||||
|
TRAJECTORY_BUILDER_nD.max_range
|
||||||
|
|
||||||
|
.. note::
|
||||||
|
|
||||||
|
In 2D, Cartographer replaces ranges further than max_range by ``TRAJECTORY_BUILDER_2D.missing_data_ray_length``. It also provides a ``max_z`` and ``min_z`` values to filter 3D point clouds into a 2D cut.
|
||||||
|
|
||||||
|
.. note::
|
||||||
|
|
||||||
|
In Cartographer configuration files, every distance is defined in meters
|
||||||
|
|
||||||
|
Distances are measured over a certain period of time, while the robot is actually moving.
|
||||||
|
However, distances are delivered by sensors "in batch" in large ROS messages.
|
||||||
|
Each of the messages' timestamp can be considered independently by Cartographer to take into account deformations caused by the robot's motion.
|
||||||
|
The more often Cartographer gets measurements, the better it becomes at unwarping the measurements to assemble a single coherent scan that could have been captured instantly.
|
||||||
|
It is therefore strongly encouraged to provide as many range data (ROS messages) by scan (a set of range data that can be matched against another scan) as possible.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_nD.num_accumulated_range_data
|
||||||
|
|
||||||
|
Range data is typically measured from a single point on the robot but in multiple angles.
|
||||||
|
This means that close surfaces (for instance the road) are very often hit and provide lots of points.
|
||||||
|
On the opposite, far objects are less often hit and offer less points.
|
||||||
|
In order to reduce the computational weight of points handling, we usually need to subsample point clouds.
|
||||||
|
However, a simple random sampling would remove points from areas where we already have a low density of measurements and the high-density areas would still have more points than needed.
|
||||||
|
To address that density problem, we can use a voxel filter that downsamples raw points into cubes of a constant size and only keeps the centroid of each cube.
|
||||||
|
|
||||||
|
A small cube size will result in a more dense data representation, causing more computations.
|
||||||
|
A large cube size will result in a data loss but will be much quicker.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_nD.voxel_filter_size
|
||||||
|
|
||||||
|
After having applied a fixed-size voxel filter, Cartographer also applies an **adaptive voxel filter**.
|
||||||
|
This filter tries to determine the optimal voxel size (under a max length) to achieve a target number of points.
|
||||||
|
In 3D, two adaptive voxel filters are used to generate a high resolution and a low resolution point clouds, their usage will be clarified in :ref:`local-slam`.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_nD.*adaptive_voxel_filter.max_length
|
||||||
|
TRAJECTORY_BUILDER_nD.*adaptive_voxel_filter.min_num_points
|
||||||
|
|
||||||
|
An Inertial Measurement Unit can be an useful source of information for SLAM because it provides an accurate direction of gravity (hence, of the ground) and a noisy but good overall indication of the robot's rotation.
|
||||||
|
In order to filter the IMU noise, gravity is observed over a certain amount of time.
|
||||||
|
If you use 2D SLAM, range data can be handled in real-time without an additional source of information so you can choose whether you'd like Cartographer to use an IMU or not.
|
||||||
|
With 3D SLAM, you need to provide an IMU because it is used as an initial guess for the orientation of the scans, greatly reducing the complexity of scan matching.
|
||||||
|
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_2D.use_imu_data
|
||||||
|
TRAJECTORY_BUILDER_nD.imu_gravity_time_constant
|
||||||
|
|
||||||
|
.. note::
|
||||||
|
|
||||||
|
In Cartographer configuration files, every time value is defined in seconds
|
||||||
|
|
||||||
|
.. _local-slam:
|
||||||
|
|
||||||
|
Local SLAM
|
||||||
|
----------
|
||||||
|
|
||||||
|
Once a scan has been assembled and filtered from multiple range data, it is ready for the local SLAM algorithm.
|
||||||
|
Local SLAM inserts a new scan into its current submap construction by **scan matching** using an initial guess from the **pose extrapolator**.
|
||||||
|
The idea behind the pose extrapolator is to use sensor data of other sensors besides the range finder to predict where the next scan should be inserted into the submap.
|
||||||
|
|
||||||
|
Two scan matching strategies are available:
|
||||||
|
|
||||||
|
- The ``CeresScanMatcher`` takes the initial guess as prior and finds the best spot where the scan match fits the submap.
|
||||||
|
It does this by interpolating the submap and sub-pixel aligning the scan.
|
||||||
|
This is fast, but cannot fix errors that are significantly larger than the resolution of the submaps.
|
||||||
|
If your sensor setup and timing is reasonable, using only the ``CeresScanMatcher`` is usually the best choice to make.
|
||||||
|
- The ``RealTimeCorrelativeScanMatcher`` can be enabled if you do not have other sensors or you do not trust them.
|
||||||
|
It uses an approach similar to how scans are matched against submaps in loop closure (described later), but instead it matches against the current submap.
|
||||||
|
The best match is then used as prior for the ``CeresScanMatcher``.
|
||||||
|
This scan matcher is very expensive and will essentially override any signal from other sensors but the range finder, but it is robust in feature rich environments.
|
||||||
|
|
||||||
|
Either way, the ``CeresScanMatcher`` can be configured to give a certain weight to each of its input.
|
||||||
|
The weight is a measure of trust into your data, this can be seen as a static covariance.
|
||||||
|
The unit of weight parameters are dimensionless quantities and can't be compared between each others.
|
||||||
|
The bigger the weight of a source of data is, the more emphasis Cartographer will put on this source of data when doing scan matching.
|
||||||
|
Sources of data include occupied space (points from the scan), translation and rotation from the pose extrapolator (or ``RealTimeCorrelativeScanMatcher``)
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_3D.ceres_scan_matcher.occupied_space_weight
|
||||||
|
TRAJECTORY_BUILDER_3D.ceres_scan_matcher.occupied_space_weight_0
|
||||||
|
TRAJECTORY_BUILDER_3D.ceres_scan_matcher.occupied_space_weight_1
|
||||||
|
TRAJECTORY_BUILDER_nD.ceres_scan_matcher.translation_weight
|
||||||
|
TRAJECTORY_BUILDER_nD.ceres_scan_matcher.rotation_weight
|
||||||
|
|
||||||
|
.. note::
|
||||||
|
|
||||||
|
In 3D, the ``occupied_space_weight_0`` and ``occupied_space_weight_1`` parameters are related, respectively, to the high resolution and low resolution filtered point clouds.
|
||||||
|
|
||||||
|
The ``CeresScanMatcher`` gets its name from `Ceres Solver`_, a library developed at Google to solve non-linear least squares problems.
|
||||||
|
The scan matching problem is modelled as the minimization of such a problem with the **motion** (a transformation matrix) between two scans being a parameter to determine.
|
||||||
|
Ceres optimizes the motion using a descent algorithm for a given number of iterations.
|
||||||
|
Ceres can be configured to adapt the convergence speed to your own needs.
|
||||||
|
|
||||||
|
.. _Ceres Solver: http://ceres-solver.org/
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_nD.ceres_scan_matcher.ceres_solver_options.use_nonmonotonic_steps
|
||||||
|
TRAJECTORY_BUILDER_nD.ceres_scan_matcher.ceres_solver_options.max_num_iterations
|
||||||
|
TRAJECTORY_BUILDER_nD.ceres_scan_matcher.ceres_solver_options.num_threads
|
||||||
|
|
||||||
|
The ``RealTimeCorrelativeScanMatcher`` can be toggled depending on the trust you have in your sensors.
|
||||||
|
It works by searching for similar scans in a **search window** which is defined by a maximum distance radius and a maximum angle radius.
|
||||||
|
When performing scan matching with scans found in this window, a different weight can be chosen for the translational and rotational components.
|
||||||
|
You can play with those weight if, for example, you know that your robot doesn't rotate a lot.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_nD.use_online_correlative_scan_matching
|
||||||
|
TRAJECTORY_BUILDER_nD.real_time_correlative_scan_matcher.linear_search_window
|
||||||
|
TRAJECTORY_BUILDER_nD.real_time_correlative_scan_matcher.angular_search_window
|
||||||
|
TRAJECTORY_BUILDER_nD.real_time_correlative_scan_matcher.translation_delta_cost_weight
|
||||||
|
TRAJECTORY_BUILDER_nD.real_time_correlative_scan_matcher.rotation_delta_cost_weight
|
||||||
|
|
||||||
|
To avoid inserting too many scans per submaps, once a motion between two scans is found by the scan matcher, it goes through a **motion filter**.
|
||||||
|
A scan is dropped if the motion that led to it is not considered as significant enough.
|
||||||
|
A scan is inserted into the current submap only if its motion is above a certain distance, angle or time threshold.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_nD.motion_filter.max_time_seconds
|
||||||
|
TRAJECTORY_BUILDER_nD.motion_filter.max_distance_meters
|
||||||
|
TRAJECTORY_BUILDER_nD.motion_filter.max_angle_radians
|
||||||
|
|
||||||
|
A submap is considered as complete when the local SLAM has received a given amount of range data.
|
||||||
|
Local SLAM drifts over time, global SLAM is used to fix this drift.
|
||||||
|
Submaps must be small enough so that the drift inside them is below the resolution, so that they are locally correct.
|
||||||
|
On the other hand, they should be large enough to be distinct for loop closure to work properly.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_nD.submaps.num_range_data
|
||||||
|
|
||||||
|
Submaps can store their range data in a couple of different data structures:
|
||||||
|
The most widely used representation is called probability grids.
|
||||||
|
However, in 2D, one can also choose to use Truncated Signed Distance Fields (TSDF).
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_2D.submaps.grid_options_2d.grid_type
|
||||||
|
|
||||||
|
Probability grids cut out space into a 2D or 3D table where each cell has a fixed size and contains the odds of being obstructed.
|
||||||
|
Odds are updated according to "*hits*" (where the range data is measured) and "*misses*" (the free space between the sensor and the measured points).
|
||||||
|
Both *hits* and *misses* can have a different weight in occupancy probability calculations giving more or less trust to occupied or free space measurements.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_2D.submaps.range_data_inserter.probability_grid_range_data_inserter.hit_probability
|
||||||
|
TRAJECTORY_BUILDER_2D.submaps.range_data_inserter.probability_grid_range_data_inserter.miss_probability
|
||||||
|
TRAJECTORY_BUILDER_3D.submaps.range_data_inserter.hit_probability
|
||||||
|
TRAJECTORY_BUILDER_3D.submaps.range_data_inserter.miss_probability
|
||||||
|
|
||||||
|
In 2D, only one probability grid per submap is stored.
|
||||||
|
In 3D, for scan matching performance reasons, two *hybrid* probability grids are used.
|
||||||
|
(the term "hybrid" only refers to an internal tree-like data representation and is abstracted to the user)
|
||||||
|
|
||||||
|
- a low resolution hybrid grid for far measurements
|
||||||
|
- a high resolution hybrid grid for close measurements
|
||||||
|
|
||||||
|
Scan matching starts by aligning far points of the low resolution point cloud with the low resolution hybrid grid and then refines the pose by aligning the close high resolution points with the high resolution hybrid grid.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER_2D.submaps.grid_options_2d.resolution
|
||||||
|
TRAJECTORY_BUILDER_3D.submaps.high_resolution
|
||||||
|
TRAJECTORY_BUILDER_3D.submaps.low_resolution
|
||||||
|
TRAJECTORY_BUILDER_3D.high_resolution_adaptive_voxel_filter.max_range
|
||||||
|
TRAJECTORY_BUILDER_3D.low_resolution_adaptive_voxel_filter.max_range
|
||||||
|
|
||||||
|
.. note::
|
||||||
|
|
||||||
|
Cartographer ROS provides an RViz plugin to visualize submaps. You can select the submaps you want to see from their number. In 3D, RViz only shows 2D projections of the 3D hybrid probability grids (in grayscale). Options are made available in RViz's left pane to switch between the low and high resolution hybrid grids visualization.
|
||||||
|
|
||||||
|
**TODO**: *Documenting TSDF configuration*
|
||||||
|
|
||||||
|
Global SLAM
|
||||||
|
-----------
|
||||||
|
|
||||||
|
While the local SLAM generates its succession of submaps, a global optimization (usually refered to as "*the optimization problem*" or "*sparse pose adjustment*") task runs in background.
|
||||||
|
Its role is to re-arrange submaps between each other so that they form a coherent global map.
|
||||||
|
For instance, this optimization is in charge of altering the currently built trajectory to properly align submaps with regards to loop closures.
|
||||||
|
|
||||||
|
The optimization is run in batches once a certain number of trajectory nodes was inserted. Depending on how frequently you need to run it, you can tune the size of these batches.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
POSE_GRAPH.optimize_every_n_nodes
|
||||||
|
|
||||||
|
.. note::
|
||||||
|
|
||||||
|
Setting POSE_GRAPH.optimize_every_n_nodes to 0 is a handy way to disable global SLAM and concentrate on the behavior of local SLAM. This is usually one of the first thing to do to tune Cartographer.
|
||||||
|
|
||||||
|
The global SLAM is a kind of "*GraphSLAM*", it is essentially a pose graph optimization which works by building **constraints** between **nodes** and submaps and then optimizing the resulting constraints graph.
|
||||||
|
Constraints can intuitively be thought of as little ropes tying all nodes together.
|
||||||
|
The sparse pose adjustement fastens those ropes altogether.
|
||||||
|
The resulting net is called the "*pose graph*".
|
||||||
|
|
||||||
|
.. note::
|
||||||
|
|
||||||
|
Constraints can be visualized in RViz, it is very handy to tune global SLAM. One can also toggle ``POSE_GRAPH.constraint_builder.log_matches`` to get regular reports of the constraints builder formatted as histograms.
|
||||||
|
|
||||||
|
- Non-global constraints (also known as inter submaps constraints) are built automatically between nodes that are closely following each other on a trajectory.
|
||||||
|
Intuitively, those "*non-global ropes*" keep the local structure of the trajectory coherent.
|
||||||
|
- Global constraints (also referred to as loop closure constraints or intra submaps contraints) are regularly searched between a new submap and previous nodes that are considered "*close enough*" in space (part of a certain **search window**) and a strong fit (a good match when running scan matching).
|
||||||
|
Intuitively, those "*global ropes*" introduce knots in the structure and firmly bring two strands closer.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
POSE_GRAPH.constraint_builder.max_constraint_distance
|
||||||
|
POSE_GRAPH.fast_correlative_scan_matcher.linear_search_window
|
||||||
|
POSE_GRAPH.fast_correlative_scan_matcher_3d.linear_xy_search_window
|
||||||
|
POSE_GRAPH.fast_correlative_scan_matcher_3d.linear_z_search_window
|
||||||
|
POSE_GRAPH.fast_correlative_scan_matcher*.angular_search_window
|
||||||
|
|
||||||
|
.. note::
|
||||||
|
|
||||||
|
In practice, global constraints can do more than finding loop closures on a single trajectory. They can also align different trajectories recorded by multiple robots but we will keep this usage and the parameters related to "global localization" out of the scope of this document.
|
||||||
|
|
||||||
|
To limit the amount of constraints (and computations), Cartographer only considers a subsampled set of all close nodes for constraints building.
|
||||||
|
This is controlled by a sampling ratio constant.
|
||||||
|
Sampling too few nodes could result in missed constraints and ineffective loop closures.
|
||||||
|
Sampling too many nodes would slow the global SLAM down and prevent real-time loop closures.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
POSE_GRAPH.constraint_builder.sampling_ratio
|
||||||
|
|
||||||
|
When a node and a submap are considered for constraint building, they go through a first scan matcher called the ``FastCorrelativeScanMatcher``.
|
||||||
|
This scan matcher has been specifically designed for Cartographer and makes real-time loop closures scan matching possible.
|
||||||
|
The ``FastCorrelativeScanMatcher`` relies on a "*Branch and bound*" mechanism to work at different grid resolutions and efficiently eliminate incorrect matchings.
|
||||||
|
This mechanism is extensively presented in the Cartographer paper presented earlier in this document.
|
||||||
|
It works on an exploration tree whose depth can be controlled.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher.branch_and_bound_depth
|
||||||
|
POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.branch_and_bound_depth
|
||||||
|
POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.full_resolution_depth
|
||||||
|
|
||||||
|
Once the ``FastCorrelativeScanMatcher`` has a good enough proposal (above a minimum score of matching), it is then fed into a Ceres Scan Matcher to refine the pose.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
POSE_GRAPH.constraint_builder.min_score
|
||||||
|
POSE_GRAPH.constraint_builder.ceres_scan_matcher_3d
|
||||||
|
POSE_GRAPH.constraint_builder.ceres_scan_matcher
|
||||||
|
|
||||||
|
When Cartographer runs *the optimization problem*, Ceres is used to rearrange submaps according to multiple *residuals*.
|
||||||
|
Residuals are calculated using weighted cost functions.
|
||||||
|
The global optimization has cost functions to take into account plenty of data sources: the global (loop closure) constraints, the non-global (matcher) constraints, the IMU acceleration and rotation measurements, the local SLAM rough pose estimations, an odometry source or a fixed frame (such as a GPS system).
|
||||||
|
The weights and Ceres options can be configured as described in the :ref:`local-slam` section.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
POSE_GRAPH.constraint_builder.loop_closure_translation_weight
|
||||||
|
POSE_GRAPH.constraint_builder.loop_closure_rotation_weight
|
||||||
|
POSE_GRAPH.matcher_translation_weight
|
||||||
|
POSE_GRAPH.matcher_rotation_weight
|
||||||
|
POSE_GRAPH.optimization_problem.*_weight
|
||||||
|
POSE_GRAPH.optimization_problem.ceres_solver_options
|
||||||
|
|
||||||
|
.. note::
|
||||||
|
|
||||||
|
One can find useful information about the residuals used in the optimization problem by toggling ``POSE_GRAPH.max_num_final_iterations``
|
||||||
|
|
||||||
|
As part of its IMU residual, the optimization problem gives some flexibility to the IMU pose and, by default, Ceres is free to optimize the extrinsic calibration between your IMU and tracking frame.
|
||||||
|
If you don't trust your IMU pose, the results of Ceres' global optimization can be logged and used to improve your extrinsic calibration.
|
||||||
|
If Ceres doesn't optimize your IMU pose correctly and you trust your extrinsic calibration enough, you can make this pose constant.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
POSE_GRAPH.optimization_problem.log_solver_summary
|
||||||
|
POSE_GRAPH.optimization_problem.use_online_imu_extrinsics_in_3d
|
||||||
|
|
||||||
|
In residuals, the influence of outliers is handled by a **Huber loss** function configured with a certain a Huber scale.
|
||||||
|
The bigger the Huber scale, `the higher is the impact`_ of (potential) outliers.
|
||||||
|
|
||||||
|
.. _the higher is the impact: https://github.com/ceres-solver/ceres-solver/blob/0d3a84fce553c9f7aab331f0895fa7b1856ef5ee/include/ceres/loss_function.h#L172
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
POSE_GRAPH.optimization_problem.huber_scale
|
||||||
|
|
||||||
|
Once the trajectory is finished, Cartographer runs a new global optimization with, typically, a lot more iterations than previous global optimizations.
|
||||||
|
This is done to polish the final result of Cartographer and usually does not need to be real-time so a large number of iterations is often a right choice.
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
POSE_GRAPH.max_num_final_iterations
|
|
@ -17,54 +17,54 @@
|
||||||
|
|
||||||
.. _assets_writer:
|
.. _assets_writer:
|
||||||
|
|
||||||
Assets writer
|
Exploiting the map generated by Cartographer ROS
|
||||||
=============
|
================================================
|
||||||
|
|
||||||
The purpose of SLAM is to compute the trajectory of a single sensor through a metric space.
|
As sensor data come in, the state of a SLAM algorithm such as Cartographer evolves to stay *the current best estimate* of a robot's trajectory and surroundings.
|
||||||
On a higher level, the input of SLAM is sensor data, its output is the best estimate of the trajectory up to this point in time.
|
The most accurate localization and mapping Cartographer can offer is therefore the one obtained when the algorithm finishes.
|
||||||
To be real-time and efficient, Cartographer throws most of the sensor data away immediately.
|
Cartographer can serialize its internal state in a ``.pbstream`` file format which is essentially a compressed protobuf file containing a snapshot of the data structures used by Cartographer internally.
|
||||||
|
|
||||||
The trajectory alone is rarely of interest.
|
To run efficiently in real-time, Cartographer throws most of its sensor data away immediately and only works with a small subset of its input, the mapping used internally (and saved in ``.pbstream`` files) is then very rough.
|
||||||
But once the best trajectory is established, the full sensor data can be used to derive and visualize information about its surroundings.
|
However, when the algorithm finishes and a best trajectory is established, it can be recombined *a posteriori* with the full sensors data to create a high resolution map.
|
||||||
|
|
||||||
Cartographer provides the assets writer for this.
|
Cartographer makes this kind of recombination possible using ``cartographer_assets_writer``.
|
||||||
Its inputs are
|
The assets writer takes as input
|
||||||
|
|
||||||
1. the original sensor data fed to SLAM in a ROS bag file,
|
1. the original sensors data that has been used to perform SLAM (in a ROS ``.bag`` file),
|
||||||
2. the cartographer state, which is contained in the ``.pbstream`` file that SLAM creates,
|
2. a cartographer state captured while performing SLAM on this sensor data (saved in a ``.pbstream`` file),
|
||||||
3. the sensor extrinsics (i.e. TF data from the bag or a URDF),
|
3. the sensor extrinsics (i.e. TF data from the bag or an URDF description),
|
||||||
4. and a pipeline configuration, which is defined in a ``.lua`` file.
|
4. and a pipeline configuration, which is defined in a ``.lua`` file.
|
||||||
|
|
||||||
The assets writer runs through the sensor data in batches with a known trajectory.
|
The assets writer runs through the ``.bag`` data in batches with the trajectory found in the ``.pbstream``.
|
||||||
It can be used to color, filter and export SLAM point cloud data in a variety of formats.
|
The pipeline can be can be used to color, filter and export SLAM point cloud data into a variety of formats.
|
||||||
For more information on what the asset writer can be used for, refer to the examples below below and the header files in `cartographer/io`_.
|
There are multiple of such points processing steps that can be interleaved in a pipeline - several ones are already available from `cartographer/io`_.
|
||||||
|
|
||||||
Sample usage
|
Sample Usage
|
||||||
------------
|
------------
|
||||||
|
|
||||||
|
When running Cartographer with an offline node, a ``.pbstream`` file is automatically saved.
|
||||||
|
For instance, with the 3D backpack example:
|
||||||
|
|
||||||
.. code-block:: bash
|
.. code-block:: bash
|
||||||
|
|
||||||
# Download the 3D backpack example bag.
|
|
||||||
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_3d/b3-2016-04-05-14-14-00.bag
|
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_3d/b3-2016-04-05-14-14-00.bag
|
||||||
|
|
||||||
# Launch the 3D offline demo.
|
|
||||||
roslaunch cartographer_ros offline_backpack_3d.launch bag_filenames:=${HOME}/Downloads/b3-2016-04-05-14-14-00.bag
|
roslaunch cartographer_ros offline_backpack_3d.launch bag_filenames:=${HOME}/Downloads/b3-2016-04-05-14-14-00.bag
|
||||||
|
|
||||||
Watch the output on the commandline until the offline node terminates.
|
Watch the output on the commandline until the node terminates.
|
||||||
It will have written ``b3-2016-04-05-14-14-00.bag.pbstream`` which represents the Cartographer state after it processed all data and finished all optimizations.
|
It will have written ``b3-2016-04-05-14-14-00.bag.pbstream`` which represents the Cartographer state after it processed all data and finished all optimizations.
|
||||||
You could have gotten the same state data by running the online node and calling:
|
|
||||||
|
When running as an online node, Cartographer doesn't know when your bag (or sensor input) ends so you need to use the exposed services to explicitly finish the current trajectory and make Cartographer serialize its current state:
|
||||||
|
|
||||||
.. code-block:: bash
|
.. code-block:: bash
|
||||||
|
|
||||||
# Finish the first trajectory. No further data will be accepted on it.
|
# Finish the first trajectory. No further data will be accepted on it.
|
||||||
rosservice call /finish_trajectory 0
|
rosservice call /finish_trajectory 0
|
||||||
|
|
||||||
# Ask Cartographer to serialize its current state.
|
|
||||||
rosservice call /write_state ${HOME}/Downloads/b3-2016-04-05-14-14-00.bag.pbstream
|
rosservice call /write_state ${HOME}/Downloads/b3-2016-04-05-14-14-00.bag.pbstream
|
||||||
|
|
||||||
Now we run the assets writer with the `sample configuration file`_ for the 3D backpack:
|
|
||||||
|
|
||||||
.. _sample configuration file: https://github.com/googlecartographer/cartographer_ros/blob/44459e18102305745c56f92549b87d8e91f434fe/cartographer_ros/configuration_files/assets_writer_backpack_3d.lua
|
Once you've retrieved your ``.pbstream`` file, you can run the assets writer with the `sample pipeline`_ for the 3D backpack:
|
||||||
|
|
||||||
|
.. _sample pipeline: https://github.com/googlecartographer/cartographer_ros/blob/44459e18102305745c56f92549b87d8e91f434fe/cartographer_ros/configuration_files/assets_writer_backpack_3d.lua
|
||||||
|
|
||||||
.. code-block:: bash
|
.. code-block:: bash
|
||||||
|
|
||||||
|
@ -72,43 +72,59 @@ Now we run the assets writer with the `sample configuration file`_ for the 3D ba
|
||||||
bag_filenames:=${HOME}/Downloads/b3-2016-04-05-14-14-00.bag \
|
bag_filenames:=${HOME}/Downloads/b3-2016-04-05-14-14-00.bag \
|
||||||
pose_graph_filename:=${HOME}/Downloads/b3-2016-04-05-14-14-00.bag.pbstream
|
pose_graph_filename:=${HOME}/Downloads/b3-2016-04-05-14-14-00.bag.pbstream
|
||||||
|
|
||||||
All output files are prefixed by ``--output_file_prefix`` which defaults to the filename of the first bag.
|
All output files are prefixed with ``--output_file_prefix`` which defaults to the filename of the first bag.
|
||||||
For the last example, if you specify ``points.ply`` in the pipeline configuration file, this will translate to ``${HOME}/Downloads/b3-2016-04-05-14-14-00.bag_points.ply``.
|
For the last example, if you specify ``points.ply`` in the pipeline configuration file, this will translate to ``${HOME}/Downloads/b3-2016-04-05-14-14-00.bag_points.ply``.
|
||||||
|
|
||||||
Configuration
|
Configuration
|
||||||
-------------
|
-------------
|
||||||
|
|
||||||
The assets writer is modeled as a pipeline.
|
The assets writer is modeled as a pipeline of `PointsProcessor`_s.
|
||||||
It consists of `PointsProcessor`_\ s and `PointsBatch`_\ s flow through it.
|
`PointsBatch`_\ s flow through each processor and they all have the chance to modify the ``PointsBatch`` before passing it on.
|
||||||
Data flows from the first processor to the next, each has the chance to modify the ``PointsBatch`` before passing it on.
|
|
||||||
|
|
||||||
.. _PointsProcessor: https://github.com/googlecartographer/cartographer/blob/30f7de1a325d6604c780f2f74d9a345ec369d12d/cartographer/io/points_processor.h
|
.. _PointsProcessor: https://github.com/googlecartographer/cartographer/blob/30f7de1a325d6604c780f2f74d9a345ec369d12d/cartographer/io/points_processor.h
|
||||||
.. _PointsBatch: https://github.com/googlecartographer/cartographer/blob/30f7de1a325d6604c780f2f74d9a345ec369d12d/cartographer/io/points_batch.h
|
.. _PointsBatch: https://github.com/googlecartographer/cartographer/blob/30f7de1a325d6604c780f2f74d9a345ec369d12d/cartographer/io/points_batch.h
|
||||||
|
|
||||||
For example the `assets_writer_backpack_3d.lua`_ uses ``min_max_range_filter`` to remove points that are either too close or too far from the sensor.
|
For example the `assets_writer_backpack_3d.lua`_ pipeline uses ``min_max_range_filter`` to remove points that are either too close or too far from the sensor.
|
||||||
After this, it writes X-Rays, then recolors the ``PointsBatch``\ s depending on the sensor frame ids and writes another set of X-Rays using these new colors.
|
After this, it saves "*X-Rays*" (translucent side views of the map), then recolors the ``PointsBatch``\ s depending on the sensor frame ids and writes another set of X-Rays using these new colors.
|
||||||
|
|
||||||
.. _assets_writer_backpack_3d.lua: https://github.com/googlecartographer/cartographer_ros/blob/44459e18102305745c56f92549b87d8e91f434fe/cartographer_ros/configuration_files/assets_writer_backpack_3d.lua
|
.. _assets_writer_backpack_3d.lua: https://github.com/googlecartographer/cartographer_ros/blob/44459e18102305745c56f92549b87d8e91f434fe/cartographer_ros/configuration_files/assets_writer_backpack_3d.lua
|
||||||
|
|
||||||
The individual ``PointsProcessor``\ s are all in the `cartographer/io`_ sub-directory and documented in their individual header files.
|
The available ``PointsProcessor``\ s are all defined in the `cartographer/io`_ sub-directory and documented in their individual header files.
|
||||||
|
|
||||||
.. _cartographer/io: https://github.com/googlecartographer/cartographer/tree/30f7de1a325d6604c780f2f74d9a345ec369d12d/cartographer/io
|
.. _cartographer/io: https://github.com/googlecartographer/cartographer/tree/f1ac8967297965b8eb6f2f4b08a538e052b5a75b/cartographer/io
|
||||||
|
|
||||||
|
* **color_points**: Colors points with a fixed color by frame_id.
|
||||||
|
* **dump_num_points**: Passes through points, but keeps track of how many points it saw and output that on Flush.
|
||||||
|
* **fixed_ratio_sampler**: Only let a fixed 'sampling_ratio' of points through. A 'sampling_ratio' of 1. makes this filter a no-op.
|
||||||
|
* **frame_id_filter**: Filters all points with blacklisted frame_id or a non-whitelisted frame id. Note that you can either specify the whitelist or the blacklist, but not both at the same time.
|
||||||
|
* **write_hybrid_grid**: Creates a hybrid grid of the points with voxels being 'voxel_size' big. 'range_data_inserter' options are used to configure the range data ray tracing through the hybrid grid.
|
||||||
|
* **intensity_to_color**: Applies ('intensity' - min) / (max - min) * 255 and color the point grey with this value for each point that comes from the sensor with 'frame_id'. If 'frame_id' is empty, this applies to all points.
|
||||||
|
* **min_max_range_filtering**: Filters all points that are farther away from their 'origin' as 'max_range' or closer than 'min_range'.
|
||||||
|
* **voxel_filter_and_remove_moving_objects**: Voxel filters the data and only passes on points that we believe are on non-moving objects.
|
||||||
|
* **write_pcd**: Streams a PCD file to disk. The header is written in 'Flush'.
|
||||||
|
* **write_ply**: Streams a PLY file to disk. The header is written in 'Flush'.
|
||||||
|
* **write_probability_grid**: Creates a probability grid with the specified 'resolution'. As all points are projected into the x-y plane the z component of the data is ignored. 'range_data_inserter' options are used to cofnigure the range data ray tracing through the probability grid.
|
||||||
|
* **write_xray_image**: Creates X-ray cuts through the points with pixels being 'voxel_size' big.
|
||||||
|
* **write_xyz**: Writes ASCII xyz points.
|
||||||
|
|
||||||
First-person visualization of point clouds
|
First-person visualization of point clouds
|
||||||
------------------------------------------
|
------------------------------------------
|
||||||
|
|
||||||
Generating a fly through of points is a two step approach:
|
Two ``PointsProcessor``\ s are of particular interest: ``pcd_writing`` and ``ply_writing`` can save a point cloud in a ``.pcd`` or ``.ply`` file format.
|
||||||
First, write a PLY file with the points you want to visualize, then use `point_cloud_viewer`_.
|
These file formats can then be used by specialized software such as `point_cloud_viewer`_ or `meshlab`_ to navigate through the high resolution map.
|
||||||
|
|
||||||
.. _point_cloud_viewer: https://github.com/googlecartographer/point_cloud_viewer
|
.. _point_cloud_viewer: https://github.com/googlecartographer/point_cloud_viewer
|
||||||
|
.. _meshlab: http://www.meshlab.net/
|
||||||
|
|
||||||
The first step is usually accomplished by using IntensityToColorPointsProcessor_ to give the points a non-white color, then writing them to a PLY using PlyWritingPointsProcessor_.
|
The typical assets writer pipeline for this outcome is composed of an IntensityToColorPointsProcessor_ giving points a non-white color, then a PlyWritingPointsProcessor_ exporting the results to a ``.ply`` point cloud.
|
||||||
An example is in `assets_writer_backpack_2d.lua`_.
|
An example of such a pipeline is in `assets_writer_backpack_2d.lua`_.
|
||||||
|
|
||||||
.. _IntensityToColorPointsProcessor: https://github.com/googlecartographer/cartographer/blob/30f7de1a325d6604c780f2f74d9a345ec369d12d/cartographer/io/intensity_to_color_points_processor.cc
|
.. _IntensityToColorPointsProcessor: https://github.com/googlecartographer/cartographer/blob/30f7de1a325d6604c780f2f74d9a345ec369d12d/cartographer/io/intensity_to_color_points_processor.cc
|
||||||
.. _PlyWritingPointsProcessor: https://github.com/googlecartographer/cartographer/blob/30f7de1a325d6604c780f2f74d9a345ec369d12d/cartographer/io/ply_writing_points_processor.h
|
.. _PlyWritingPointsProcessor: https://github.com/googlecartographer/cartographer/blob/30f7de1a325d6604c780f2f74d9a345ec369d12d/cartographer/io/ply_writing_points_processor.h
|
||||||
.. _assets_writer_backpack_2d.lua: https://github.com/googlecartographer/cartographer_ros/blob/44459e18102305745c56f92549b87d8e91f434fe/cartographer_ros/configuration_files/assets_writer_backpack_2d.lua
|
.. _assets_writer_backpack_2d.lua: https://github.com/googlecartographer/cartographer_ros/blob/44459e18102305745c56f92549b87d8e91f434fe/cartographer_ros/configuration_files/assets_writer_backpack_2d.lua
|
||||||
|
|
||||||
Once you have the PLY, follow the README of `point_cloud_viewer`_ to generate an on-disk octree data structure which can be viewed by one of the viewers in the same repo.
|
Once you have the ``.ply``, follow the README of `point_cloud_viewer`_ to generate an on-disk octree data structure which can be viewed by one of the viewers (SDL or web based) in the same repo.
|
||||||
|
|
||||||
.. _point_cloud_viewer: https://github.com/googlecartographer/point_cloud_viewer
|
.. _point_cloud_viewer: https://github.com/googlecartographer/point_cloud_viewer
|
||||||
|
|
||||||
|
.. image:: point_cloud_viewer_demo_3d.jpg
|
||||||
|
|
|
@ -0,0 +1,70 @@
|
||||||
|
.. Copyright 2018 The Cartographer Authors
|
||||||
|
|
||||||
|
.. Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
you may not use this file except in compliance with the License.
|
||||||
|
You may obtain a copy of the License at
|
||||||
|
|
||||||
|
.. http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
|
||||||
|
.. Unless required by applicable law or agreed to in writing, software
|
||||||
|
distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
See the License for the specific language governing permissions and
|
||||||
|
limitations under the License.
|
||||||
|
|
||||||
|
==========================
|
||||||
|
Compiling Cartographer ROS
|
||||||
|
==========================
|
||||||
|
|
||||||
|
System Requirements
|
||||||
|
===================
|
||||||
|
|
||||||
|
The Cartographer ROS requirements are the same as `the ones from Cartographer`_.
|
||||||
|
|
||||||
|
The following `ROS distributions`_ are currently supported:
|
||||||
|
|
||||||
|
* Indigo
|
||||||
|
* Kinetic
|
||||||
|
* Lunar
|
||||||
|
* Melodic
|
||||||
|
|
||||||
|
.. _the ones from Cartographer: https://google-cartographer.readthedocs.io/en/latest/#system-requirements
|
||||||
|
.. _ROS distributions: http://wiki.ros.org/Distributions
|
||||||
|
|
||||||
|
Building & Installation
|
||||||
|
=======================
|
||||||
|
|
||||||
|
In order to build Cartographer ROS, we recommend using `wstool <http://wiki.ros.org/wstool>`_ and `rosdep
|
||||||
|
<http://wiki.ros.org/rosdep>`_. For faster builds, we also recommend using
|
||||||
|
`Ninja <https://ninja-build.org>`_.
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
|
sudo apt-get update
|
||||||
|
sudo apt-get install -y python-wstool python-rosdep ninja-build
|
||||||
|
|
||||||
|
Create a new cartographer_ros workspace in 'catkin_ws'.
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
|
mkdir catkin_ws
|
||||||
|
cd catkin_ws
|
||||||
|
wstool init src
|
||||||
|
wstool merge -t src https://raw.githubusercontent.com/googlecartographer/cartographer_ros/master/cartographer_ros.rosinstall
|
||||||
|
wstool update -t src
|
||||||
|
|
||||||
|
Install cartographer_ros' dependencies (proto3 and deb packages).
|
||||||
|
The command 'sudo rosdep init' will print an error if you have already executed it since installing ROS. This error can be ignored.
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
|
src/cartographer/scripts/install_proto3.sh
|
||||||
|
sudo rosdep init
|
||||||
|
rosdep update
|
||||||
|
rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y
|
||||||
|
|
||||||
|
Build and install.
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
|
catkin_make_isolated --install --use-ninja
|
|
@ -12,9 +12,9 @@
|
||||||
See the License for the specific language governing permissions and
|
See the License for the specific language governing permissions and
|
||||||
limitations under the License.
|
limitations under the License.
|
||||||
|
|
||||||
=============
|
=========================================
|
||||||
Configuration
|
Lua configuration reference documentation
|
||||||
=============
|
=========================================
|
||||||
|
|
||||||
Note that Cartographer's ROS integration uses `tf2`_, thus all frame IDs are
|
Note that Cartographer's ROS integration uses `tf2`_, thus all frame IDs are
|
||||||
expected to contain only a frame name (lower-case with underscores) and no
|
expected to contain only a frame name (lower-case with underscores) and no
|
||||||
|
@ -51,10 +51,26 @@ provide_odom_frame
|
||||||
If enabled, the local, non-loop-closed, continuous pose will be published as
|
If enabled, the local, non-loop-closed, continuous pose will be published as
|
||||||
the *odom_frame* in the *map_frame*.
|
the *odom_frame* in the *map_frame*.
|
||||||
|
|
||||||
|
publish_frame_projected_to_2d
|
||||||
|
If enabled, the published pose will be restricted to a pure 2D pose (no roll,
|
||||||
|
pitch, or z-offset). This prevents potentially unwanted out-of-plane poses in
|
||||||
|
2D mode that can occur due to the pose extrapolation step (e.g. if the pose
|
||||||
|
shall be published as a 'base-footprint'-like frame)
|
||||||
|
|
||||||
use_odometry
|
use_odometry
|
||||||
If enabled, subscribes to `nav_msgs/Odometry`_ on the topic "odom". Odometry
|
If enabled, subscribes to `nav_msgs/Odometry`_ on the topic "odom". Odometry
|
||||||
must be provided in this case, and the information will be included in SLAM.
|
must be provided in this case, and the information will be included in SLAM.
|
||||||
|
|
||||||
|
use_nav_sat
|
||||||
|
If enabled, subscribes to `sensor_msgs/NavSatFix`_ on the topic "fix".
|
||||||
|
Navigation data must be provided in this case, and the information will be
|
||||||
|
included in the global SLAM.
|
||||||
|
|
||||||
|
use_landmarks
|
||||||
|
If enabled, subscribes to `cartographer_ros_msgs/LandmarkList`_ on the topic
|
||||||
|
"landmarks". Landmarks must be provided in this case, and the information
|
||||||
|
will be included in SLAM.
|
||||||
|
|
||||||
num_laser_scans
|
num_laser_scans
|
||||||
Number of laser scan topics to subscribe to. Subscribes to
|
Number of laser scan topics to subscribe to. Subscribes to
|
||||||
`sensor_msgs/LaserScan`_ on the "scan" topic for one laser scanner, or topics
|
`sensor_msgs/LaserScan`_ on the "scan" topic for one laser scanner, or topics
|
||||||
|
@ -91,6 +107,21 @@ trajectory_publish_period_sec
|
||||||
Interval in seconds at which to publish the trajectory markers, e.g. 30e-3
|
Interval in seconds at which to publish the trajectory markers, e.g. 30e-3
|
||||||
for 30 milliseconds.
|
for 30 milliseconds.
|
||||||
|
|
||||||
|
rangefinder_sampling_ratio
|
||||||
|
Fixed ratio sampling for range finders messages.
|
||||||
|
|
||||||
|
odometry_sampling_ratio
|
||||||
|
Fixed ratio sampling for odometry messages.
|
||||||
|
|
||||||
|
fixed_frame_sampling_ratio
|
||||||
|
Fixed ratio sampling for fixed frame messages.
|
||||||
|
|
||||||
|
imu_sampling_ratio
|
||||||
|
Fixed ratio sampling for IMU messages.
|
||||||
|
|
||||||
|
landmarks_sampling_ratio
|
||||||
|
Fixed ratio sampling for landmarks messages.
|
||||||
|
|
||||||
.. _REP 105: http://www.ros.org/reps/rep-0105.html
|
.. _REP 105: http://www.ros.org/reps/rep-0105.html
|
||||||
.. _ROS Names: http://wiki.ros.org/Names
|
.. _ROS Names: http://wiki.ros.org/Names
|
||||||
.. _nav_msgs/OccupancyGrid: http://docs.ros.org/api/nav_msgs/html/msg/OccupancyGrid.html
|
.. _nav_msgs/OccupancyGrid: http://docs.ros.org/api/nav_msgs/html/msg/OccupancyGrid.html
|
||||||
|
@ -98,4 +129,6 @@ trajectory_publish_period_sec
|
||||||
.. _sensor_msgs/LaserScan: http://docs.ros.org/api/sensor_msgs/html/msg/LaserScan.html
|
.. _sensor_msgs/LaserScan: http://docs.ros.org/api/sensor_msgs/html/msg/LaserScan.html
|
||||||
.. _sensor_msgs/MultiEchoLaserScan: http://docs.ros.org/api/sensor_msgs/html/msg/MultiEchoLaserScan.html
|
.. _sensor_msgs/MultiEchoLaserScan: http://docs.ros.org/api/sensor_msgs/html/msg/MultiEchoLaserScan.html
|
||||||
.. _sensor_msgs/PointCloud2: http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html
|
.. _sensor_msgs/PointCloud2: http://docs.ros.org/api/sensor_msgs/html/msg/PointCloud2.html
|
||||||
|
.. _sensor_msgs/NavSatFix: http://docs.ros.org/api/sensor_msgs/html/msg/NavSatFix.html
|
||||||
|
.. _cartographer_ros_msgs/LandmarkList: https://github.com/googlecartographer/cartographer_ros/blob/4b39ee68c7a4d518bf8d01a509331e2bc1f514a0/cartographer_ros_msgs/msg/LandmarkList.msg
|
||||||
.. _tf2: http://wiki.ros.org/tf2
|
.. _tf2: http://wiki.ros.org/tf2
|
||||||
|
|
Binary file not shown.
After Width: | Height: | Size: 1.2 MiB |
|
@ -12,35 +12,70 @@
|
||||||
See the License for the specific language governing permissions and
|
See the License for the specific language governing permissions and
|
||||||
limitations under the License.
|
limitations under the License.
|
||||||
|
|
||||||
=====
|
======================================
|
||||||
Demos
|
Running Cartographer ROS on a demo bag
|
||||||
=====
|
======================================
|
||||||
|
|
||||||
|
Now that Cartographer and Cartographer's ROS integration are installed, you can
|
||||||
|
download example bags (e.g. 2D and 3D backpack collections of the
|
||||||
|
`Deutsches Museum <https://en.wikipedia.org/wiki/Deutsches_Museum>`_) to a
|
||||||
|
known location, in this case ``~/Downloads``, and use ``roslaunch`` to bring up
|
||||||
|
the demo.
|
||||||
|
|
||||||
|
The launch files will bring up ``roscore`` and ``rviz`` automatically.
|
||||||
|
|
||||||
|
.. warning:: When you want to run cartographer_ros, you might need to source your ROS environment by running ``source install_isolated/setup.bash`` first (replace bash with zsh if your shell is zsh)
|
||||||
|
|
||||||
|
Deutsches Museum
|
||||||
|
================
|
||||||
|
|
||||||
|
Download and launch the 2D backpack demo:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
|
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_2d/cartographer_paper_deutsches_museum.bag
|
||||||
|
roslaunch cartographer_ros demo_backpack_2d.launch bag_filename:=${HOME}/Downloads/cartographer_paper_deutsches_museum.bag
|
||||||
|
|
||||||
|
Download and launch the 3D backpack demo:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
|
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_3d/with_intensities/b3-2016-04-05-14-14-00.bag
|
||||||
|
roslaunch cartographer_ros demo_backpack_3d.launch bag_filename:=${HOME}/Downloads/b3-2016-04-05-14-14-00.bag
|
||||||
|
|
||||||
Pure localization
|
Pure localization
|
||||||
=================
|
=================
|
||||||
|
|
||||||
.. code-block:: bash
|
Pure localization uses 2 different bags. The first one is used to generate the map, the second to run pure localization.
|
||||||
|
|
||||||
|
Download the 2D bags from the Deutsche Museum:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
# Pure localization demo in 2D: We use 2 different 2D bags from the Deutsche
|
|
||||||
# Museum. The first one is used to generate the map, the second to run
|
|
||||||
# pure localization.
|
|
||||||
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_2d/b2-2016-04-05-14-44-52.bag
|
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_2d/b2-2016-04-05-14-44-52.bag
|
||||||
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_2d/b2-2016-04-27-12-31-41.bag
|
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_2d/b2-2016-04-27-12-31-41.bag
|
||||||
# Generate the map: Run the next command, wait until cartographer_offline_node finishes.
|
|
||||||
|
Generate the map (wait until cartographer_offline_node finishes) and then run pure localization:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
roslaunch cartographer_ros offline_backpack_2d.launch bag_filenames:=${HOME}/Downloads/b2-2016-04-05-14-44-52.bag
|
roslaunch cartographer_ros offline_backpack_2d.launch bag_filenames:=${HOME}/Downloads/b2-2016-04-05-14-44-52.bag
|
||||||
# Run pure localization:
|
|
||||||
roslaunch cartographer_ros demo_backpack_2d_localization.launch \
|
roslaunch cartographer_ros demo_backpack_2d_localization.launch \
|
||||||
load_state_filename:=${HOME}/Downloads/b2-2016-04-05-14-44-52.bag.pbstream \
|
load_state_filename:=${HOME}/Downloads/b2-2016-04-05-14-44-52.bag.pbstream \
|
||||||
bag_filename:=${HOME}/Downloads/b2-2016-04-27-12-31-41.bag
|
bag_filename:=${HOME}/Downloads/b2-2016-04-27-12-31-41.bag
|
||||||
|
|
||||||
# Pure localization demo in 3D: We use 2 different 3D bags from the Deutsche
|
Download the 3D bags from the Deutsche Museum:
|
||||||
# Museum. The first one is used to generate the map, the second to run
|
|
||||||
# pure localization.
|
.. code-block:: bash
|
||||||
|
|
||||||
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_3d/b3-2016-04-05-13-54-42.bag
|
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_3d/b3-2016-04-05-13-54-42.bag
|
||||||
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_3d/b3-2016-04-05-15-52-20.bag
|
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_3d/b3-2016-04-05-15-52-20.bag
|
||||||
# Generate the map: Run the next command, wait until cartographer_offline_node finishes.
|
|
||||||
|
Generate the map (wait until cartographer_offline_node finishes) and then run pure localization:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
roslaunch cartographer_ros offline_backpack_3d.launch bag_filenames:=${HOME}/Downloads/b3-2016-04-05-13-54-42.bag
|
roslaunch cartographer_ros offline_backpack_3d.launch bag_filenames:=${HOME}/Downloads/b3-2016-04-05-13-54-42.bag
|
||||||
# Run pure localization:
|
|
||||||
roslaunch cartographer_ros demo_backpack_3d_localization.launch \
|
roslaunch cartographer_ros demo_backpack_3d_localization.launch \
|
||||||
load_state_filename:=${HOME}/Downloads/b3-2016-04-05-13-54-42.bag.pbstream \
|
load_state_filename:=${HOME}/Downloads/b3-2016-04-05-13-54-42.bag.pbstream \
|
||||||
bag_filename:=${HOME}/Downloads/b3-2016-04-05-15-52-20.bag
|
bag_filename:=${HOME}/Downloads/b3-2016-04-05-15-52-20.bag
|
||||||
|
@ -63,32 +98,29 @@ Static landmarks
|
||||||
Revo LDS
|
Revo LDS
|
||||||
========
|
========
|
||||||
|
|
||||||
.. code-block:: bash
|
Download and launch an example bag captured from a low-cost Revo Laser Distance Sensor from Neato Robotics vacuum cleaners:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
# Download the Revo LDS example bag.
|
|
||||||
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/revo_lds/cartographer_paper_revo_lds.bag
|
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/revo_lds/cartographer_paper_revo_lds.bag
|
||||||
|
|
||||||
# Launch the Revo LDS demo.
|
|
||||||
roslaunch cartographer_ros demo_revo_lds.launch bag_filename:=${HOME}/Downloads/cartographer_paper_revo_lds.bag
|
roslaunch cartographer_ros demo_revo_lds.launch bag_filename:=${HOME}/Downloads/cartographer_paper_revo_lds.bag
|
||||||
|
|
||||||
PR2
|
PR2
|
||||||
===
|
===
|
||||||
|
|
||||||
.. code-block:: bash
|
Download and launch an example bag captured from a PR2 R&D humanoid robot from Willow Garage:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
# Download the PR2 example bag.
|
|
||||||
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/pr2/2011-09-15-08-32-46.bag
|
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/pr2/2011-09-15-08-32-46.bag
|
||||||
|
|
||||||
# Launch the PR2 demo.
|
|
||||||
roslaunch cartographer_ros demo_pr2.launch bag_filename:=${HOME}/Downloads/2011-09-15-08-32-46.bag
|
roslaunch cartographer_ros demo_pr2.launch bag_filename:=${HOME}/Downloads/2011-09-15-08-32-46.bag
|
||||||
|
|
||||||
Taurob Tracker
|
Taurob Tracker
|
||||||
==============
|
==============
|
||||||
|
|
||||||
.. code-block:: bash
|
Download and launch an example bag captured from a Taurob Tracker teleoperation robot:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
# Download the Taurob Tracker example bag.
|
|
||||||
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/taurob_tracker/taurob_tracker_simulation.bag
|
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/taurob_tracker/taurob_tracker_simulation.bag
|
||||||
|
|
||||||
# Launch the Taurob Tracker demo.
|
|
||||||
roslaunch cartographer_ros demo_taurob_tracker.launch bag_filename:=${HOME}/Downloads/taurob_tracker_simulation.bag
|
roslaunch cartographer_ros demo_taurob_tracker.launch bag_filename:=${HOME}/Downloads/taurob_tracker_simulation.bag
|
||||||
|
|
Binary file not shown.
After Width: | Height: | Size: 101 KiB |
|
@ -0,0 +1,46 @@
|
||||||
|
.. Copyright 2018 The Cartographer Authors
|
||||||
|
|
||||||
|
.. Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
you may not use this file except in compliance with the License.
|
||||||
|
You may obtain a copy of the License at
|
||||||
|
|
||||||
|
.. http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
|
||||||
|
.. Unless required by applicable law or agreed to in writing, software
|
||||||
|
distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
See the License for the specific language governing permissions and
|
||||||
|
limitations under the License.
|
||||||
|
|
||||||
|
================
|
||||||
|
Getting involved
|
||||||
|
================
|
||||||
|
|
||||||
|
Cartographer is developed in the open and allows anyone to contribute to the project.
|
||||||
|
There are multiple ways to get involved!
|
||||||
|
|
||||||
|
Twice a month, the project hosts "Open House Hangouts" sessions that are essentially meetings open to everyone to join in.
|
||||||
|
The call typically recaps the recent and ongoing development around Cartographer and Cartographer ROS.
|
||||||
|
The developers are then open to questions from the community, this is a great time to ask about contribution ideas.
|
||||||
|
If you don't feel like talking or being seen, you are free to join anyway and skulk!
|
||||||
|
The slides are also made available after each session but there is no video recording.
|
||||||
|
|
||||||
|
If you want to stay tuned with announcements (such as new major releases or new open house sessions), you can join `the Cartographer mailing list`_ although you can not interact with this mailing list anymore.
|
||||||
|
|
||||||
|
.. _the Cartographer mailing list: https://groups.google.com/forum/#!forum/google-cartographer
|
||||||
|
|
||||||
|
If you think you've found an issue in Cartographer, you are welcome to open a `GitHub issue`_ but don't forget to provide a way to reproduce your bug!
|
||||||
|
Typically, join a ``.bag`` and a link to a fork of the ``cartographer_ros`` repository containing your configuration and launch files.
|
||||||
|
|
||||||
|
.. _GitHub issue: https://github.com/googlecartographer/cartographer/issues
|
||||||
|
|
||||||
|
If you have an idea of a significant change that should be documented and discussed before finding its way into Cartographer, you should submit it as a pull request to `the RFCs repository`_ first.
|
||||||
|
Simpler changes can also be discussed in GitHub issues so that developers can help you get things right from the first try.
|
||||||
|
|
||||||
|
.. _the RFCs repository: https://github.com/googlecartographer/rfcs
|
||||||
|
|
||||||
|
If you want to contribute code or documentation, this is done through `GitHub pull requests`_.
|
||||||
|
However, make sure you have signed (online) the `Contributor License Agreement`_ first!
|
||||||
|
|
||||||
|
.. _GitHub pull requests: https://github.com/googlecartographer/cartographer/pulls
|
||||||
|
.. _Contributor License Agreement: https://github.com/googlecartographer/cartographer/blob/master/CONTRIBUTING.md
|
|
@ -0,0 +1,80 @@
|
||||||
|
.. Copyright 2018 The Cartographer Authors
|
||||||
|
|
||||||
|
.. Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
you may not use this file except in compliance with the License.
|
||||||
|
You may obtain a copy of the License at
|
||||||
|
|
||||||
|
.. http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
|
||||||
|
.. Unless required by applicable law or agreed to in writing, software
|
||||||
|
distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
See the License for the specific language governing permissions and
|
||||||
|
limitations under the License.
|
||||||
|
|
||||||
|
=============
|
||||||
|
Going further
|
||||||
|
=============
|
||||||
|
|
||||||
|
Cartographer is not only a great SLAM algorithm, it also comes with a fully-featured implementation that brings lots of "extra" features.
|
||||||
|
This page lists some of those less known functionalities.
|
||||||
|
|
||||||
|
More input
|
||||||
|
==========
|
||||||
|
|
||||||
|
If you have a source of odometry (such as a wheel encoder) publishing on a ``nav_msgs/Odometry`` topic and want to use it to improve Cartographer's localization, you can add an input to your ``.lua`` configuration files:
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
use_odometry = true
|
||||||
|
|
||||||
|
The messages will be expected on the ``odom`` topic.
|
||||||
|
|
||||||
|
A GPS publishing on a ``sensor_msgs/NavSatFix`` topic named ``fix`` can improve the global SLAM:
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
use_nav_sat = true
|
||||||
|
|
||||||
|
For landmarks publishing on a ``cartographer_ros_msgs/LandmarkList`` (`message defined in cartographer_ros`_) topic named ``landmarks``:
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
use_landmarks = true
|
||||||
|
|
||||||
|
.. _message defined in cartographer_ros: https://github.com/googlecartographer/cartographer_ros/blob/4b39ee68c7a4d518bf8d01a509331e2bc1f514a0/cartographer_ros_msgs/msg/LandmarkList.msg
|
||||||
|
|
||||||
|
Localization only
|
||||||
|
=================
|
||||||
|
|
||||||
|
If you have a map you are happy with and want to reduce computations, you can use the localization-only mode of Cartographer which will run SLAM against the existing map and won't build a new one.
|
||||||
|
This is enabled by running ``cartographer_node`` with a ``-load_state_filename`` argument and by defining the following line in your lua config:
|
||||||
|
|
||||||
|
.. code-block:: lua
|
||||||
|
|
||||||
|
TRAJECTORY_BUILDER.pure_localization_trimmer = {
|
||||||
|
max_submaps_to_keep = 3,
|
||||||
|
}
|
||||||
|
|
||||||
|
IMU Calibration
|
||||||
|
===============
|
||||||
|
|
||||||
|
When performing the global optimization, Ceres tries to improve the pose between your IMU and range finding sensors.
|
||||||
|
A well chosen acquisition with lots of loop closure constraints (for instance if your robot goes on a straight line and then back) can improve the quality of those corrections and become a reliable source of pose correction.
|
||||||
|
You can then use Cartographer as part of your calibration process to improve the quality of your robot's extrinsic calibration.
|
||||||
|
|
||||||
|
Multi-trajectories SLAM
|
||||||
|
=======================
|
||||||
|
|
||||||
|
Cartographer can perform SLAM from multiple robots emiting data in parallel.
|
||||||
|
The global SLAM is able to detect shared paths and will merge the maps built by the different robots as soon as it becomes possible.
|
||||||
|
This is achieved through the usage of two ROS services ``start_trajectory`` and ``finish_trajectory``. (refer to the ROS API reference documentation for more details on their usage)
|
||||||
|
|
||||||
|
Cloud integration with gRPC
|
||||||
|
===========================
|
||||||
|
|
||||||
|
Cartographer is built around Protobuf messages which make it very flexible and interoperable.
|
||||||
|
One of the advantages of that architecture is that it is easy to distribute on machines spread over the Internet.
|
||||||
|
The typical use case would be a fleet of robots navigating on a known map, they could have their SLAM algorithm run on a remote powerful centralized localization server running a multi-trajectories Cartographer instance.
|
||||||
|
|
||||||
|
**TODO**: Instructions on how to get started with a gRPC Cartographer instance
|
|
@ -16,94 +16,27 @@
|
||||||
Cartographer ROS Integration
|
Cartographer ROS Integration
|
||||||
============================
|
============================
|
||||||
|
|
||||||
.. toctree::
|
|
||||||
:maxdepth: 2
|
|
||||||
|
|
||||||
configuration
|
|
||||||
tuning
|
|
||||||
ros_api
|
|
||||||
assets_writer
|
|
||||||
demos
|
|
||||||
data
|
|
||||||
faq
|
|
||||||
|
|
||||||
`Cartographer`_ is a system that provides real-time simultaneous localization
|
`Cartographer`_ is a system that provides real-time simultaneous localization
|
||||||
and mapping (`SLAM`_) in 2D and 3D across multiple platforms and sensor
|
and mapping (`SLAM`_) in 2D and 3D across multiple platforms and sensor
|
||||||
configurations. This project provides Cartographer's ROS integration.
|
configurations. This project provides Cartographer's ROS integration.
|
||||||
|
|
||||||
|
.. image:: demo_2d.gif
|
||||||
|
|
||||||
|
.. toctree::
|
||||||
|
:maxdepth: 2
|
||||||
|
|
||||||
|
compilation
|
||||||
|
demos
|
||||||
|
your_bag
|
||||||
|
algo_walkthrough
|
||||||
|
tuning
|
||||||
|
assets_writer
|
||||||
|
going_further
|
||||||
|
getting_involved
|
||||||
|
configuration
|
||||||
|
ros_api
|
||||||
|
data
|
||||||
|
faq
|
||||||
|
|
||||||
.. _Cartographer: https://github.com/googlecartographer/cartographer
|
.. _Cartographer: https://github.com/googlecartographer/cartographer
|
||||||
.. _SLAM: https://en.wikipedia.org/wiki/Simultaneous_localization_and_mapping
|
.. _SLAM: https://en.wikipedia.org/wiki/Simultaneous_localization_and_mapping
|
||||||
|
|
||||||
System Requirements
|
|
||||||
===================
|
|
||||||
|
|
||||||
See Cartographer's :ref:`system requirements <cartographer:system-requirements>`.
|
|
||||||
|
|
||||||
The following `ROS distributions`_ are currently supported:
|
|
||||||
|
|
||||||
* Indigo
|
|
||||||
* Kinetic
|
|
||||||
|
|
||||||
.. _ROS distributions: http://wiki.ros.org/Distributions
|
|
||||||
|
|
||||||
Building & Installation
|
|
||||||
=======================
|
|
||||||
|
|
||||||
We recommend using `wstool <http://wiki.ros.org/wstool>`_ and `rosdep
|
|
||||||
<http://wiki.ros.org/rosdep>`_. For faster builds, we also recommend using
|
|
||||||
`Ninja <https://ninja-build.org>`_.
|
|
||||||
|
|
||||||
.. code-block:: bash
|
|
||||||
|
|
||||||
# Install wstool and rosdep.
|
|
||||||
sudo apt-get update
|
|
||||||
sudo apt-get install -y python-wstool python-rosdep ninja-build
|
|
||||||
|
|
||||||
# Create a new workspace in 'catkin_ws'.
|
|
||||||
mkdir catkin_ws
|
|
||||||
cd catkin_ws
|
|
||||||
wstool init src
|
|
||||||
|
|
||||||
# Merge the cartographer_ros.rosinstall file and fetch code for dependencies.
|
|
||||||
wstool merge -t src https://raw.githubusercontent.com/googlecartographer/cartographer_ros/master/cartographer_ros.rosinstall
|
|
||||||
wstool update -t src
|
|
||||||
|
|
||||||
# Install proto3.
|
|
||||||
src/cartographer/scripts/install_proto3.sh
|
|
||||||
|
|
||||||
# Install deb dependencies.
|
|
||||||
# The command 'sudo rosdep init' will print an error if you have already
|
|
||||||
# executed it since installing ROS. This error can be ignored.
|
|
||||||
sudo rosdep init
|
|
||||||
rosdep update
|
|
||||||
rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y
|
|
||||||
|
|
||||||
# Build and install.
|
|
||||||
catkin_make_isolated --install --use-ninja
|
|
||||||
source install_isolated/setup.bash
|
|
||||||
|
|
||||||
Running the demos
|
|
||||||
=================
|
|
||||||
|
|
||||||
Now that Cartographer and Cartographer's ROS integration are installed,
|
|
||||||
download the example bags (e.g. 2D and 3D backpack collections of the
|
|
||||||
`Deutsches Museum <https://en.wikipedia.org/wiki/Deutsches_Museum>`_) to a
|
|
||||||
known location, in this case ``~/Downloads``, and use ``roslaunch`` to bring up
|
|
||||||
the demo:
|
|
||||||
|
|
||||||
.. code-block:: bash
|
|
||||||
|
|
||||||
# Download the 2D backpack example bag.
|
|
||||||
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_2d/cartographer_paper_deutsches_museum.bag
|
|
||||||
|
|
||||||
# Launch the 2D backpack demo.
|
|
||||||
roslaunch cartographer_ros demo_backpack_2d.launch bag_filename:=${HOME}/Downloads/cartographer_paper_deutsches_museum.bag
|
|
||||||
|
|
||||||
# Download the 3D backpack example bag.
|
|
||||||
wget -P ~/Downloads https://storage.googleapis.com/cartographer-public-data/bags/backpack_3d/with_intensities/b3-2016-04-05-14-14-00.bag
|
|
||||||
|
|
||||||
# Launch the 3D backpack demo.
|
|
||||||
roslaunch cartographer_ros demo_backpack_3d.launch bag_filename:=${HOME}/Downloads/b3-2016-04-05-14-14-00.bag
|
|
||||||
|
|
||||||
The launch files will bring up ``roscore`` and ``rviz`` automatically.
|
|
||||||
See :doc:`demos` for additional demos including localization and various robots.
|
|
||||||
|
|
Binary file not shown.
After Width: | Height: | Size: 85 KiB |
Binary file not shown.
After Width: | Height: | Size: 1.4 MiB |
|
@ -12,9 +12,11 @@
|
||||||
See the License for the specific language governing permissions and
|
See the License for the specific language governing permissions and
|
||||||
limitations under the License.
|
limitations under the License.
|
||||||
|
|
||||||
=======
|
===============================
|
||||||
ROS API
|
ROS API reference documentation
|
||||||
=======
|
===============================
|
||||||
|
|
||||||
|
.. image:: nodes_graph_demo_2d.jpg
|
||||||
|
|
||||||
Cartographer Node
|
Cartographer Node
|
||||||
=================
|
=================
|
||||||
|
@ -116,6 +118,8 @@ read_metrics (`cartographer_ros_msgs/ReadMetrics`_)
|
||||||
Required tf Transforms
|
Required tf Transforms
|
||||||
----------------------
|
----------------------
|
||||||
|
|
||||||
|
.. image:: frames_demo_2d.jpg
|
||||||
|
|
||||||
Transforms from all incoming sensor data frames to the :doc:`configured
|
Transforms from all incoming sensor data frames to the :doc:`configured
|
||||||
<configuration>` *tracking_frame* and *published_frame* must be available.
|
<configuration>` *tracking_frame* and *published_frame* must be available.
|
||||||
Typically, these are published periodically by a `robot_state_publisher` or a
|
Typically, these are published periodically by a `robot_state_publisher` or a
|
||||||
|
|
|
@ -16,35 +16,13 @@
|
||||||
.. cartographer_ros SHA: 99c23b6ac7874f7974e9ed808ace841da6f2c8b0
|
.. cartographer_ros SHA: 99c23b6ac7874f7974e9ed808ace841da6f2c8b0
|
||||||
.. TODO(hrapp): mention insert_free_space somewhere
|
.. TODO(hrapp): mention insert_free_space somewhere
|
||||||
|
|
||||||
Tuning
|
Tuning methodology
|
||||||
======
|
==================
|
||||||
|
|
||||||
Tuning Cartographer is unfortunately really difficult.
|
Tuning Cartographer is unfortunately really difficult.
|
||||||
The system has many parameters many of which affect each other.
|
The system has many parameters many of which affect each other.
|
||||||
This tuning guide tries to explain a principled approach on concrete examples.
|
This tuning guide tries to explain a principled approach on concrete examples.
|
||||||
|
|
||||||
Two systems
|
|
||||||
-----------
|
|
||||||
|
|
||||||
Cartographer can be seen as two separate, but related systems.
|
|
||||||
The first one is local SLAM (sometimes also called frontend).
|
|
||||||
Its job is to build a locally consistent set of submaps and tie them together, but it will drift over time.
|
|
||||||
Most of its options can be found in `trajectory_builder_2d.lua`_ for 2D and `trajectory_builder_3d.lua`_ for 3D.
|
|
||||||
|
|
||||||
.. _trajectory_builder_2d.lua: https://github.com/googlecartographer/cartographer/blob/aba4575d937df4c9697f61529200c084f2562584/configuration_files/trajectory_builder_2d.lua
|
|
||||||
.. _trajectory_builder_3d.lua: https://github.com/googlecartographer/cartographer/blob/aba4575d937df4c9697f61529200c084f2562584/configuration_files/trajectory_builder_3d.lua
|
|
||||||
|
|
||||||
The other system is global SLAM (sometimes called the backend).
|
|
||||||
It runs in background threads and its main job is to find loop closure constraints.
|
|
||||||
It does that by scan-matching scans against submaps.
|
|
||||||
It also incorporates other sensor data to get a higher level view and identify the most consistent global solution.
|
|
||||||
In 3D, it also tries to find the direction of gravity.
|
|
||||||
Most of its options can be found in `pose_graph.lua`_
|
|
||||||
|
|
||||||
.. _pose_graph.lua: https://github.com/googlecartographer/cartographer/blob/aba4575d937df4c9697f61529200c084f2562584/configuration_files/pose_graph.lua
|
|
||||||
|
|
||||||
On a higher abstraction, the job of local SLAM is to generate good submaps and the job of global SLAM is to tie them most consistently together.
|
|
||||||
|
|
||||||
Built-in tools
|
Built-in tools
|
||||||
--------------
|
--------------
|
||||||
|
|
||||||
|
@ -87,31 +65,9 @@ So let's turn off global SLAM to not mess with our tuning.
|
||||||
Correct size of submaps
|
Correct size of submaps
|
||||||
^^^^^^^^^^^^^^^^^^^^^^^
|
^^^^^^^^^^^^^^^^^^^^^^^
|
||||||
|
|
||||||
Local SLAM drifts over time, only loop closure can fix this drift.
|
|
||||||
Submaps must be small enough so that the drift inside them is below the resolution, so that they are locally correct.
|
|
||||||
On the other hand, they should be large enough to be being distinct for loop closure to work properly.
|
|
||||||
The size of submaps is configured through ``TRAJECTORY_BUILDER_2D.submaps.num_range_data``.
|
The size of submaps is configured through ``TRAJECTORY_BUILDER_2D.submaps.num_range_data``.
|
||||||
Looking at the individual submaps for this example they already fit the two constraints rather well, so we assume this parameter is well tuned.
|
Looking at the individual submaps for this example they already fit the two constraints rather well, so we assume this parameter is well tuned.
|
||||||
|
|
||||||
The choice of scan matchers
|
|
||||||
^^^^^^^^^^^^^^^^^^^^^^^^^^^
|
|
||||||
|
|
||||||
The idea behind local SLAM is to use sensor data of other sensors besides the range finder to predict where the next scan should be inserted into the submap.
|
|
||||||
Then, the ``CeresScanMatcher`` takes this as prior and finds the best spot where the scan match fits the submap.
|
|
||||||
It does this by interpolating the submap and sub-pixel aligning the scan.
|
|
||||||
This is fast, but cannot fix errors that are significantly larger than the resolution of the submaps.
|
|
||||||
If your sensor setup and timing is reasonable, using only the ``CeresScanMatcher`` is usually the best choice to make.
|
|
||||||
|
|
||||||
If you do not have other sensors or you do not trust them, Cartographer also provides a ``RealTimeCorrelativeScanMatcher``.
|
|
||||||
It uses an approach similar to how scans are matched against submaps in loop closure, but instead it matches against the current submap.
|
|
||||||
The best match is then used as prior for the ``CeresScanMatcher``.
|
|
||||||
This scan matcher is very expensive and will essentially override any signal from other sensors but the range finder, but it is robust in feature rich environments.
|
|
||||||
|
|
||||||
Tuning the correlative scan matcher
|
|
||||||
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
|
|
||||||
|
|
||||||
TODO
|
|
||||||
|
|
||||||
Tuning the ``CeresScanMatcher``
|
Tuning the ``CeresScanMatcher``
|
||||||
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
|
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
|
||||||
|
|
||||||
|
@ -225,7 +181,7 @@ If a separate odometry source is used as an input for local SLAM (``use_odometry
|
||||||
|
|
||||||
There are in total four parameters that allow us to tune the individual weights of local SLAM and odometry in the optimization:
|
There are in total four parameters that allow us to tune the individual weights of local SLAM and odometry in the optimization:
|
||||||
|
|
||||||
.. code-block:: lua
|
.. code-block:: lua
|
||||||
|
|
||||||
POSE_GRAPH.optimization_problem.local_slam_pose_translation_weight
|
POSE_GRAPH.optimization_problem.local_slam_pose_translation_weight
|
||||||
POSE_GRAPH.optimization_problem.local_slam_pose_rotation_weight
|
POSE_GRAPH.optimization_problem.local_slam_pose_rotation_weight
|
||||||
|
@ -236,3 +192,18 @@ We can set these weights depending on how much we trust either local SLAM or the
|
||||||
By default, odometry is weighted into global optimization similar to local slam (scan matching) poses.
|
By default, odometry is weighted into global optimization similar to local slam (scan matching) poses.
|
||||||
However, odometry from wheel encoders often has a high uncertainty in rotation.
|
However, odometry from wheel encoders often has a high uncertainty in rotation.
|
||||||
In this case, the rotation weight can be reduced, even down to zero.
|
In this case, the rotation weight can be reduced, even down to zero.
|
||||||
|
|
||||||
|
Still have a problem ?
|
||||||
|
----------------------
|
||||||
|
|
||||||
|
If you can't get Cartographer to work reliably on your data, you can open a `GitHub issue`_ asking for help.
|
||||||
|
Developers are keen to help, but they can only be helpful if you follow `an issue template`_ containing the result of ``rosbag_validate``, a link to a fork of ``cartographer_ros`` with your config and a link to a ``.bag`` file reproducing your problem.
|
||||||
|
|
||||||
|
.. note::
|
||||||
|
|
||||||
|
There are already lots of GitHub issues with all sorts of problems solved by the developers. Going through `the closed issues of cartographer_ros`_ and `of cartographer`_ is a great way to learn more about Cartographer and maybe find a solution to your problem !
|
||||||
|
|
||||||
|
.. _GitHub issue: https://github.com/googlecartographer/cartographer_ros/issues
|
||||||
|
.. _an issue template: https://github.com/googlecartographer/cartographer_ros/issues/new?labels=question
|
||||||
|
.. _the closed issues of cartographer_ros: https://github.com/googlecartographer/cartographer_ros/issues?q=is%3Aissue+is%3Aclosed
|
||||||
|
.. _of cartographer: https://github.com/googlecartographer/cartographer_ros/issues?q=is%3Aissue+is%3Aclosed
|
||||||
|
|
|
@ -0,0 +1,140 @@
|
||||||
|
.. Copyright 2018 The Cartographer Authors
|
||||||
|
|
||||||
|
.. Licensed under the Apache License, Version 2.0 (the "License");
|
||||||
|
you may not use this file except in compliance with the License.
|
||||||
|
You may obtain a copy of the License at
|
||||||
|
|
||||||
|
.. http://www.apache.org/licenses/LICENSE-2.0
|
||||||
|
|
||||||
|
.. Unless required by applicable law or agreed to in writing, software
|
||||||
|
distributed under the License is distributed on an "AS IS" BASIS,
|
||||||
|
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
|
||||||
|
See the License for the specific language governing permissions and
|
||||||
|
limitations under the License.
|
||||||
|
|
||||||
|
========================================
|
||||||
|
Running Cartographer ROS on your own bag
|
||||||
|
========================================
|
||||||
|
|
||||||
|
Now that you've run Cartographer ROS on a couple of provided bags, you can go ahead and make Cartographer work with your own data.
|
||||||
|
Find a ``.bag`` recording you would like to use for SLAM and go through this tutorial.
|
||||||
|
|
||||||
|
.. warning:: When you want to run cartographer_ros, you might need to source your ROS environment by running ``source install_isolated/setup.bash`` first (replace bash with zsh if your shell is zsh)
|
||||||
|
|
||||||
|
Validate your bag
|
||||||
|
=================
|
||||||
|
|
||||||
|
Cartographer ROS provides a tool named ``cartographer_rosbag_validate`` to automatically analyze data present in your bag.
|
||||||
|
It is generally a good idea to run this tool before trying to tune Cartographer for incorrect data.
|
||||||
|
|
||||||
|
It benefits from the experience of the Cartographer authors and can detect a variety of mistakes commonly found in bags.
|
||||||
|
For instance, if a ``sensor_msgs/Imu`` topic is detected, the tool will make sure that the gravity vector has not been removed from the IMU measurements because the gravity norm is used by Cartographer to determine the direction of the ground.
|
||||||
|
|
||||||
|
The tool can also provide tips on how to improve the quality of your data.
|
||||||
|
For example, with a Velodyne LIDAR, it is recommended to have one ``sensor_msgs/PointCloud2`` message per UDP packet sent by the sensor instead of one message per revolution.
|
||||||
|
With that granularity, Cartographer is then able to unwarp the point clouds deformation caused by the robot's motion and results in better reconstruction.
|
||||||
|
|
||||||
|
If you have sourced your Cartographer ROS environment, you can simply run the tool like this:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
|
cartographer_rosbag_validate -bag_filename your_bag.bag
|
||||||
|
|
||||||
|
Create a .lua configuration
|
||||||
|
===========================
|
||||||
|
|
||||||
|
Cartographer is highly flexible and can be configured to work on a variety of robots.
|
||||||
|
The robot configuration is read from a ``options`` data structure that must be defined from a Lua script.
|
||||||
|
The example configurations are defined in ``src/cartographer_ros/cartographer_ros/configuration_files`` and installed in ``install_isolated/share/cartographer_ros/configuration_files/``.
|
||||||
|
|
||||||
|
.. note:: Ideally, a .lua configuration should be robot-specific and not bag-specific.
|
||||||
|
|
||||||
|
You can start by copying one of the example and then adapt it to your own need. If you want to use 3D SLAM:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
|
cp install_isolated/share/cartographer_ros/configuration_files/backpack_3d.lua install_isolated/share/cartographer_ros/configuration_files/my_robot.lua
|
||||||
|
|
||||||
|
If you want to use 2D SLAM:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
|
cp install_isolated/share/cartographer_ros/configuration_files/backpack_3d.lua install_isolated/share/cartographer_ros/configuration_files/my_robot.lua
|
||||||
|
|
||||||
|
You can then edit ``my_robot.lua`` to suit the needs of your robot.
|
||||||
|
The values defined in the ``options`` block define how the Cartographer ROS frontend should interface with your bag.
|
||||||
|
The values defined after the ``options`` paragraph are used to tune the inner-working of Cartographer, we will ignore these for now.
|
||||||
|
|
||||||
|
.. seealso:: The `reference documentation of the Cartographer ROS configuration values`_ and of `the Cartographer configuration values`_.
|
||||||
|
|
||||||
|
.. _reference documentation of the Cartographer ROS configuration values: https://google-cartographer-ros.readthedocs.io/en/latest/configuration.html
|
||||||
|
|
||||||
|
.. _the Cartographer configuration values: https://google-cartographer.readthedocs.io/en/latest/configuration.html
|
||||||
|
|
||||||
|
Among the values you need to adapt, you probably have to provide the TF frame IDs of your environment and robot in ``map_frame``, ``tracking_frame``, ``published_frame`` and ``odom_frame``.
|
||||||
|
|
||||||
|
.. note:: You can either distribute your robot's TF tree from a ``/tf`` topic in your bag or define it in a ``.urdf`` robot definition.
|
||||||
|
|
||||||
|
.. warning:: You should trust your poses! A small offset on the link between your robot and IMU or LIDAR can lead to incoherent map reconstructions. Cartographer can usually correct small pose errors but not everything!
|
||||||
|
|
||||||
|
The other values you need to define are related to the number and type of sensors you would like to use.
|
||||||
|
|
||||||
|
- ``num_laser_scans``: Number of ``sensor_msgs/LaserScan`` topics you'll use.
|
||||||
|
- ``num_multi_echo_laser_scans``: Number of ``sensor_msgs/MultiEchoLaserScan`` topics you'll use.
|
||||||
|
- ``num_point_clouds``: Number of ``sensor_msgs/PointCloud2`` topics you'll use.
|
||||||
|
|
||||||
|
You can also enable the usage of landmarks and GPS as additional sources of localization using ``use_landmarks`` and ``use_nav_sat``. The rest of the variables in the ``options`` block should typically be left untouched.
|
||||||
|
|
||||||
|
However, there is one global variable that you absolutely need to adapt to the needs of your bag: ``TRAJECTORY_BUILDER_3D.num_accumulated_range_data`` or ``TRAJECTORY_BUILDER_2D.num_accumulated_range_data``.
|
||||||
|
This variable defines the number of messages required to construct a full scan (typically, a full revolution).
|
||||||
|
If you follow ``cartographer_rosbag_validate``'s advices and use 100 ROS messages per scan, you can set this variable to 100.
|
||||||
|
If you have two range finding sensors (for instance, two LIDARs) providing their full scans all at once, you should set this variable to 2.
|
||||||
|
|
||||||
|
Create .launch files for your SLAM scenarios
|
||||||
|
============================================
|
||||||
|
|
||||||
|
You may have noticed that each demo introduced in the previous section was run with a different roslaunch command.
|
||||||
|
The recommended usage of Cartographer is indeed to provide a custom ``.launch`` file per robot and type of SLAM.
|
||||||
|
The example ``.launch`` files are defined in ``src/cartographer_ros/cartographer_ros/launch`` and installed in ``install_isolated/share/cartographer_ros/launch/``.
|
||||||
|
|
||||||
|
Start by copying one of the provided example:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
|
cp install_isolated/share/cartographer_ros/launch/backpack_3d.launch install_isolated/share/cartographer_ros/launch/my_robot.launch
|
||||||
|
cp install_isolated/share/cartographer_ros/launch/demo_backpack_3d.launch install_isolated/share/cartographer_ros/launch/demo_my_robot.launch
|
||||||
|
cp install_isolated/share/cartographer_ros/launch/offline_backpack_3d.launch install_isolated/share/cartographer_ros/launch/offline_my_robot.launch
|
||||||
|
cp install_isolated/share/cartographer_ros/launch/demo_backpack_3d_localization.launch install_isolated/share/cartographer_ros/launch/demo_my_robot_localization.launch
|
||||||
|
cp install_isolated/share/cartographer_ros/launch/assets_writer_backpack_3d.launch install_isolated/share/cartographer_ros/launch/assets_writer_my_robot.launch
|
||||||
|
|
||||||
|
- ``my_robot.launch`` is meant to be used on the robot to execute SLAM online (in real time) with real sensors data.
|
||||||
|
- ``demo_my_robot.launch`` is meant to be used from a development machine and expects a ``bag_filename`` argument to replay data from a recording. This launch file also spawns a rviz window configured to visualize Cartographer's state.
|
||||||
|
- ``offline_my_robot.launch`` is very similar to ``demo_my_robot.launch`` but tries to execute SLAM as fast as possible. This can make map building significantly faster. This launch file can also use multiple bag files provided to the ``bag_filenames`` argument.
|
||||||
|
- ``demo_my_robot_localization.launch`` is very similar to ``demo_my_robot.launch`` but expects a ``load_state_filename`` argument pointing to a ``.pbstream`` recording of a previous Cartographer execution. The previous recording will be used as a pre-computed map and Cartographer will only perform localization on this map.
|
||||||
|
- ``assets_writer_my_robot.launch`` is used to extract data out of a ``.pstream`` recording of a previous Cartographer execution.
|
||||||
|
|
||||||
|
Again, a few adaptations need to be made to those files to suit your robot.
|
||||||
|
|
||||||
|
- Every parameter given to ``-configuration_basename`` should be adapted to point to ``my_robot.lua``.
|
||||||
|
- If you decided to use a ``.urdf`` description of your robot, you should place your description in ``install_isolated/share/cartographer_ros/urdf`` and adapt the ``robot_description`` parameter to point to your file name.
|
||||||
|
- If you decided to use ``/tf`` messages, you can remove the ``robot_description`` parameter, the ``robot_state_publisher`` node and the lines statring with ``-urdf``.
|
||||||
|
- If the topic names published by your bag or sensors don't match the ones expected by Cartographer ROS, you can use ``<remap>`` elements to redirect your topics. The expected topic names depend on the type of range finding devices you use.
|
||||||
|
|
||||||
|
.. note::
|
||||||
|
|
||||||
|
- The IMU topic is expected to be named "imu"
|
||||||
|
- If you use only one ``sensor_msgs/LaserScan`` topic, it is expected to be named ``scan``. If you have more, they should be named ``scan_1``, ``scan_2`` etc...
|
||||||
|
- If you use only one ``sensor_msgs/MultiEchoLaserScan`` topic, it is expected to be named ``echoes``. If you have more, they should be named ``echoes_1``, ``echoes_2`` etc...
|
||||||
|
- If you use only one ``sensor_msgs/PointCloud2`` topic, it is expected be named ``points2``. If you have more, they should be named ``points2_1``, ``points2_2``, etc...
|
||||||
|
|
||||||
|
Try your configuration
|
||||||
|
======================
|
||||||
|
|
||||||
|
Everything is setup! You can now start Cartographer with:
|
||||||
|
|
||||||
|
.. code-block:: bash
|
||||||
|
|
||||||
|
roslaunch cartographer_ros my_robot.launch bag_filename:=/path/to/your_bag.bag
|
||||||
|
|
||||||
|
If you are lucky enough, everything should already work as expected.
|
||||||
|
However, you might have some problems that require tuning.
|
Loading…
Reference in New Issue