Compare commits

...

10 Commits

Author SHA1 Message Date
Bo Chen c138034db0
Remove Kinetic and fix CI (#1746)
* remove kinetic from CI and docs, EOL distribution
* fix CI badge
* Update REST call for github API
2022-10-27 19:36:29 +02:00
Daisuke Sato 741beb64ce
Fix build error on Ubuntu 20.04 + ROS Noetic/Melodic (#1745)
* Fix build error on Ubuntu 20.04 + ROS Noetic

Signed-off-by: Daisuke Sato <tiryoh@gmail.com>
2022-09-20 15:10:53 +02:00
Christian Clauss a727ea8f6c
Fix typos discovered by codespell (#1684)
Signed-off-by: Christian Clauss <cclauss@me.com>
2022-09-13 14:34:12 +02:00
iotboy 062513df85
fix error of document (#1689)
TRAJECTORY_BUILDER_2D.submaps.grid_options_2d.resolution

Signed-off-by: iotboy <iotboy@163.com>
2022-09-13 14:33:41 +02:00
Mitchell Allain 4af3de9182
Fix parameter name in algo walkthrough (#1690)
Fix reference to `POSE_GRAPH.log_residual_histograms`

Signed-off-by: Mitchell Allain <allain.mitch@gmail.com>
2022-09-13 14:33:01 +02:00
jeongmyunglee 3fef3e6eca
Jeongmyung Lee <leeejeongmyung@gmail.com> (#1735)
Signed-off-by: Jeongmyung Lee <leeejeongmyung@gmail.com>
2022-09-13 14:32:25 +02:00
Linh Nguyen 8bcb34f4ca
Add option to ignore out of order sensor message (#1737)
Check IMU and Odometry data before extrapolation

Signed-off-by: Linh Nguyen <linh.nguyen@enway.ai>
2022-09-13 14:32:09 +02:00
Jonathan Huber c06879b635
[docs] Fix parameter name of publish_tracked_pose (#1620)
Signed-off-by: Jonathan Huber <jonathan.huber@enway.ai>
2021-05-04 13:43:20 +02:00
Michael Grupp 305605bd3a
Remove inactive mailing list from docs. (#1612)
Signed-off-by: Michael Grupp <grupp@magazino.eu>
2021-04-19 14:01:18 +02:00
Mohamed Ahmed 151c56312d
typo fix (#1591)
Signed-off-by: mohamedsayed18 <mohamed95.a.s@gmail.com>
2021-01-29 11:47:57 +01:00
20 changed files with 121 additions and 132 deletions

View File

@ -22,7 +22,6 @@ cache:
- /home/travis/docker/
env:
- ROS_RELEASE=kinetic DOCKER_CACHE_FILE=/home/travis/docker/kinetic-cache.tar.gz
- ROS_RELEASE=melodic DOCKER_CACHE_FILE=/home/travis/docker/melodic-cache.tar.gz
- ROS_RELEASE=noetic DOCKER_CACHE_FILE=/home/travis/docker/noetic-cache.tar.gz
@ -34,5 +33,5 @@ before_install:
install: true
script:
- docker build ${TRAVIS_BUILD_DIR} -t cartographer_ros:${ROS_RELEASE} -f Dockerfile.${ROS_RELEASE} --build-arg github_token=${GITHUB_TOKEN}
- scripts/build_docker.sh $GITHUB_TOKEN
- scripts/save_docker_cache.sh

View File

@ -1,80 +0,0 @@
# Copyright 2016 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.
FROM osrf/ros:kinetic-desktop
ARG CARTOGRAPHER_VERSION=master
# We require a GitHub access token to be passed.
ARG github_token
# Xenial's base image doesn't ship with sudo.
RUN apt-get update && apt-get install -y sudo
# First, we invalidate the entire cache if cartographer-project/cartographer has
# changed. This file's content changes whenever master changes. See:
# http://stackoverflow.com/questions/36996046/how-to-prevent-dockerfile-caching-git-clone
ADD https://api.github.com/repos/cartographer-project/cartographer/git/refs/heads/master?access_token=$github_token \
cartographer_ros/cartographer_version.json
# wstool needs the updated rosinstall file to clone the correct repos.
COPY cartographer_ros.rosinstall cartographer_ros/
COPY scripts/prepare_catkin_workspace.sh cartographer_ros/scripts/
RUN CARTOGRAPHER_VERSION=$CARTOGRAPHER_VERSION \
cartographer_ros/scripts/prepare_catkin_workspace.sh
# rosdep needs the updated package.xml files to install the correct debs.
COPY cartographer_ros/package.xml catkin_ws/src/cartographer_ros/cartographer_ros/
COPY cartographer_ros_msgs/package.xml catkin_ws/src/cartographer_ros/cartographer_ros_msgs/
COPY cartographer_rviz/package.xml catkin_ws/src/cartographer_ros/cartographer_rviz/
COPY scripts/install_debs.sh cartographer_ros/scripts/
RUN cartographer_ros/scripts/install_debs.sh
# Install Abseil and proto3.
RUN /catkin_ws/src/cartographer/scripts/install_abseil.sh
RUN /catkin_ws/src/cartographer/scripts/install_proto3.sh
# Build, install, and test all packages individually to allow caching. The
# ordering of these steps must match the topological package ordering as
# determined by Catkin.
COPY scripts/install.sh cartographer_ros/scripts/
COPY scripts/catkin_test_results.sh cartographer_ros/scripts/
RUN cartographer_ros/scripts/install.sh --pkg cartographer && \
cartographer_ros/scripts/install.sh --pkg cartographer --make-args test
COPY cartographer_ros_msgs catkin_ws/src/cartographer_ros/cartographer_ros_msgs/
RUN cartographer_ros/scripts/install.sh --pkg cartographer_ros_msgs && \
cartographer_ros/scripts/install.sh --pkg cartographer_ros_msgs \
--catkin-make-args run_tests && \
cartographer_ros/scripts/catkin_test_results.sh build_isolated/cartographer_ros_msgs
COPY cartographer_ros catkin_ws/src/cartographer_ros/cartographer_ros/
RUN cartographer_ros/scripts/install.sh --pkg cartographer_ros && \
cartographer_ros/scripts/install.sh --pkg cartographer_ros \
--catkin-make-args run_tests && \
cartographer_ros/scripts/catkin_test_results.sh build_isolated/cartographer_ros
COPY cartographer_rviz catkin_ws/src/cartographer_ros/cartographer_rviz/
RUN cartographer_ros/scripts/install.sh --pkg cartographer_rviz && \
cartographer_ros/scripts/install.sh --pkg cartographer_rviz \
--catkin-make-args run_tests && \
cartographer_ros/scripts/catkin_test_results.sh build_isolated/cartographer_rviz
COPY scripts/ros_entrypoint.sh /
RUN rm -rf /var/lib/apt/lists/*
# A BTRFS bug may prevent us from cleaning up these directories.
# https://btrfs.wiki.kernel.org/index.php/Problem_FAQ#I_cannot_delete_an_empty_directory
RUN rm -rf cartographer_ros catkin_ws || true

View File

@ -15,24 +15,22 @@
FROM osrf/ros:melodic-desktop
ARG CARTOGRAPHER_VERSION=master
# We require a GitHub access token to be passed.
ARG github_token
ARG CARTOGRAPHER_SHA=LATEST
# Bionic's base image doesn't ship with sudo.
RUN apt-get update && apt-get install -y sudo
# First, we invalidate the entire cache if cartographer-project/cartographer has
# changed. This file's content changes whenever master changes. See:
# http://stackoverflow.com/questions/36996046/how-to-prevent-dockerfile-caching-git-clone
ADD https://api.github.com/repos/cartographer-project/cartographer/git/refs/heads/master?access_token=$github_token \
cartographer_ros/cartographer_version.json
# wstool needs the updated rosinstall file to clone the correct repos.
COPY cartographer_ros.rosinstall cartographer_ros/
COPY scripts/prepare_catkin_workspace.sh cartographer_ros/scripts/
RUN CARTOGRAPHER_VERSION=$CARTOGRAPHER_VERSION \
cartographer_ros/scripts/prepare_catkin_workspace.sh
# First, we invalidate the entire cache if cartographer-project/cartographer has
# changed. CARTOGRAPHER_SHA ARG content changes whenever master changes. See:
# http://stackoverflow.com/questions/36996046/how-to-prevent-dockerfile-caching-git-clone
RUN CARTOGRAPHER_SHA=$CARTOGRAPHER_SHA \
CARTOGRAPHER_VERSION=$CARTOGRAPHER_VERSION \
cartographer_ros/scripts/prepare_catkin_workspace.sh && \
sed -i -e "s%<depend>libabsl-dev</depend>%<\!--<depend>libabsl-dev</depend>-->%g" catkin_ws/src/cartographer/package.xml
# rosdep needs the updated package.xml files to install the correct debs.
COPY cartographer_ros/package.xml catkin_ws/src/cartographer_ros/cartographer_ros/

View File

@ -15,9 +15,7 @@
FROM osrf/ros:noetic-desktop
ARG CARTOGRAPHER_VERSION=master
# We require a GitHub access token to be passed.
ARG github_token
ARG CARTOGRAPHER_SHA=LATEST
# Prevent any interaction required by apt-get.
# https://stackoverflow.com/questions/22466255
@ -26,17 +24,17 @@ ARG DEBIAN_FRONTEND=noninteractive
# ROS Noetic's base image doesn't ship with sudo and git.
RUN apt-get update && apt-get install -y sudo git
# First, we invalidate the entire cache if cartographer-project/cartographer has
# changed. This file's content changes whenever master changes. See:
# http://stackoverflow.com/questions/36996046/how-to-prevent-dockerfile-caching-git-clone
ADD https://api.github.com/repos/cartographer-project/cartographer/git/refs/heads/master?access_token=$github_token \
cartographer_ros/cartographer_version.json
# wstool needs the updated rosinstall file to clone the correct repos.
COPY cartographer_ros.rosinstall cartographer_ros/
COPY scripts/prepare_catkin_workspace.sh cartographer_ros/scripts/
RUN CARTOGRAPHER_VERSION=$CARTOGRAPHER_VERSION \
cartographer_ros/scripts/prepare_catkin_workspace.sh
# First, we invalidate the entire cache if cartographer-project/cartographer has
# changed. CARTOGRAPHER_SHA ARG content changes whenever master changes. See:
# http://stackoverflow.com/questions/36996046/how-to-prevent-dockerfile-caching-git-clone
RUN CARTOGRAPHER_SHA=$CARTOGRAPHER_SHA \
CARTOGRAPHER_VERSION=$CARTOGRAPHER_VERSION \
cartographer_ros/scripts/prepare_catkin_workspace.sh && \
sed -i -e "s%<depend>libabsl-dev</depend>%<\!--<depend>libabsl-dev</depend>-->%g" catkin_ws/src/cartographer/package.xml
# rosdep needs the updated package.xml files to install the correct debs.
COPY cartographer_ros/package.xml catkin_ws/src/cartographer_ros/cartographer_ros/

View File

@ -45,10 +45,10 @@ at `our Contribution page`_.
.. _our Contribution page: https://github.com/cartographer-project/cartographer_ros/blob/master/CONTRIBUTING.md
.. |build| image:: https://travis-ci.org/cartographer-project/cartographer_ros.svg?branch=master
.. |build| image:: https://app.travis-ci.com/cartographer-project/cartographer_ros.svg?branch=master
:alt: Build Status
:scale: 100%
:target: https://travis-ci.org/cartographer-project/cartographer_ros
:target: https://app.travis-ci.com/cartographer-project/cartographer_ros
.. |docs| image:: https://readthedocs.org/projects/google-cartographer-ros/badge/?version=latest
:alt: Documentation Status
:scale: 100%

View File

@ -146,7 +146,7 @@ AssetsWriter::AssetsWriter(const std::string& pose_graph_filename,
<< "Pose graphs contains " << pose_graph_.trajectory_size()
<< " trajectories while " << bag_filenames_.size()
<< " bags were provided. This tool requires one bag for each "
"trajectory in the same order as the correponding trajectories in the "
"trajectory in the same order as the corresponding trajectories in the "
"pose graph proto.";
// This vector must outlive the pipeline.

View File

@ -138,6 +138,7 @@ int MapBuilderBridge::AddTrajectory(
CHECK_EQ(sensor_bridges_.count(trajectory_id), 0);
sensor_bridges_[trajectory_id] = absl::make_unique<SensorBridge>(
trajectory_options.num_subdivisions_per_laser_scan,
trajectory_options.ignore_out_of_order_messages,
trajectory_options.tracking_frame,
node_options_.lookup_transform_timeout_sec, tf_buffer_,
map_builder_->GetTrajectoryBuilder(trajectory_id));

View File

@ -771,7 +771,8 @@ void Node::HandleOdometryMessage(const int trajectory_id,
}
auto sensor_bridge_ptr = map_builder_bridge_.sensor_bridge(trajectory_id);
auto odometry_data_ptr = sensor_bridge_ptr->ToOdometryData(msg);
if (odometry_data_ptr != nullptr) {
if (odometry_data_ptr != nullptr &&
!sensor_bridge_ptr->IgnoreMessage(sensor_id, odometry_data_ptr->time)) {
extrapolators_.at(trajectory_id).AddOdometryData(*odometry_data_ptr);
}
sensor_bridge_ptr->HandleOdometryMessage(sensor_id, msg);
@ -808,7 +809,8 @@ void Node::HandleImuMessage(const int trajectory_id,
}
auto sensor_bridge_ptr = map_builder_bridge_.sensor_bridge(trajectory_id);
auto imu_data_ptr = sensor_bridge_ptr->ToImuData(msg);
if (imu_data_ptr != nullptr) {
if (imu_data_ptr != nullptr &&
!sensor_bridge_ptr->IgnoreMessage(sensor_id, imu_data_ptr->time)) {
extrapolators_.at(trajectory_id).AddImuData(*imu_data_ptr);
}
sensor_bridge_ptr->HandleImuMessage(sensor_id, msg);

View File

@ -41,10 +41,11 @@ const std::string& CheckNoLeadingSlash(const std::string& frame_id) {
SensorBridge::SensorBridge(
const int num_subdivisions_per_laser_scan,
const std::string& tracking_frame,
const bool ignore_out_of_order_messages, const std::string& tracking_frame,
const double lookup_transform_timeout_sec, tf2_ros::Buffer* const tf_buffer,
carto::mapping::TrajectoryBuilderInterface* const trajectory_builder)
: num_subdivisions_per_laser_scan_(num_subdivisions_per_laser_scan),
ignore_out_of_order_messages_(ignore_out_of_order_messages),
tf_bridge_(tracking_frame, lookup_transform_timeout_sec, tf_buffer),
trajectory_builder_(trajectory_builder) {}
@ -61,11 +62,31 @@ std::unique_ptr<carto::sensor::OdometryData> SensorBridge::ToOdometryData(
time, ToRigid3d(msg->pose.pose) * sensor_to_tracking->inverse()});
}
bool SensorBridge::IgnoreMessage(const std::string& sensor_id,
cartographer::common::Time sensor_time) {
if (!ignore_out_of_order_messages_) {
return false;
}
auto it = latest_sensor_time_.find(sensor_id);
if (it == latest_sensor_time_.end()) {
return false;
}
return sensor_time <= it->second;
}
void SensorBridge::HandleOdometryMessage(
const std::string& sensor_id, const nav_msgs::Odometry::ConstPtr& msg) {
std::unique_ptr<carto::sensor::OdometryData> odometry_data =
ToOdometryData(msg);
if (odometry_data != nullptr) {
if (IgnoreMessage(sensor_id, odometry_data->time)) {
LOG(WARNING) << "Ignored odometry message from sensor " << sensor_id
<< " because sensor time " << odometry_data->time
<< " is not before last odometry message time "
<< latest_sensor_time_[sensor_id];
return;
}
latest_sensor_time_[sensor_id] = odometry_data->time;
trajectory_builder_->AddSensorData(
sensor_id,
carto::sensor::OdometryData{odometry_data->time, odometry_data->pose});
@ -146,6 +167,14 @@ void SensorBridge::HandleImuMessage(const std::string& sensor_id,
const sensor_msgs::Imu::ConstPtr& msg) {
std::unique_ptr<carto::sensor::ImuData> imu_data = ToImuData(msg);
if (imu_data != nullptr) {
if (IgnoreMessage(sensor_id, imu_data->time)) {
LOG(WARNING) << "Ignored IMU message from sensor " << sensor_id
<< " because sensor time " << imu_data->time
<< " is not before last IMU message time "
<< latest_sensor_time_[sensor_id];
return;
}
latest_sensor_time_[sensor_id] = imu_data->time;
trajectory_builder_->AddSensorData(
sensor_id,
carto::sensor::ImuData{imu_data->time, imu_data->linear_acceleration,
@ -232,6 +261,14 @@ void SensorBridge::HandleRangefinder(
const auto sensor_to_tracking =
tf_bridge_.LookupToTracking(time, CheckNoLeadingSlash(frame_id));
if (sensor_to_tracking != nullptr) {
if (IgnoreMessage(sensor_id, time)) {
LOG(WARNING) << "Ignored Rangefinder message from sensor " << sensor_id
<< " because sensor time " << time
<< " is not before last Rangefinder message time "
<< latest_sensor_time_[sensor_id];
return;
}
latest_sensor_time_[sensor_id] = time;
trajectory_builder_->AddSensorData(
sensor_id, carto::sensor::TimedPointCloudData{
time, sensor_to_tracking->translation().cast<float>(),

View File

@ -43,8 +43,9 @@ namespace cartographer_ros {
class SensorBridge {
public:
explicit SensorBridge(
int num_subdivisions_per_laser_scan, const std::string& tracking_frame,
double lookup_transform_timeout_sec, tf2_ros::Buffer* tf_buffer,
int num_subdivisions_per_laser_scan, bool ignore_out_of_order_messages,
const std::string& tracking_frame, double lookup_transform_timeout_sec,
tf2_ros::Buffer* tf_buffer,
::cartographer::mapping::TrajectoryBuilderInterface* trajectory_builder);
SensorBridge(const SensorBridge&) = delete;
@ -73,6 +74,8 @@ class SensorBridge {
const sensor_msgs::PointCloud2::ConstPtr& msg);
const TfBridge& tf_bridge() const;
bool IgnoreMessage(const std::string& sensor_id,
::cartographer::common::Time sensor_time);
private:
void HandleLaserScan(
@ -85,8 +88,10 @@ class SensorBridge {
const ::cartographer::sensor::TimedPointCloud& ranges);
const int num_subdivisions_per_laser_scan_;
const bool ignore_out_of_order_messages_;
std::map<std::string, cartographer::common::Time>
sensor_to_previous_subdivision_time_;
std::map<std::string, cartographer::common::Time> latest_sensor_time_;
const TfBridge tf_bridge_;
::cartographer::mapping::TrajectoryBuilderInterface* const
trajectory_builder_;

View File

@ -76,6 +76,12 @@ TrajectoryOptions CreateTrajectoryOptions(
lua_parameter_dictionary->GetDouble("imu_sampling_ratio");
options.landmarks_sampling_ratio =
lua_parameter_dictionary->GetDouble("landmarks_sampling_ratio");
if (lua_parameter_dictionary->HasKey("ignore_out_of_order")) {
options.ignore_out_of_order_messages =
lua_parameter_dictionary->GetBool("ignore_out_of_order");
} else {
options.ignore_out_of_order_messages = false;
}
CheckTrajectoryOptions(options);
return options;
}

View File

@ -36,6 +36,7 @@ struct TrajectoryOptions {
bool use_nav_sat;
bool use_landmarks;
bool publish_frame_projected_to_2d;
bool ignore_out_of_order_messages;
int num_laser_scans;
int num_multi_echo_laser_scans;
int num_subdivisions_per_laser_scan;

View File

@ -153,7 +153,7 @@ Sources of data include occupied space (points from the scan), translation and r
.. code-block:: lua
TRAJECTORY_BUILDER_3D.ceres_scan_matcher.occupied_space_weight
TRAJECTORY_BUILDER_2D.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
@ -253,7 +253,7 @@ Scan matching starts by aligning far points of the low resolution point cloud wi
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.
While the local SLAM generates its succession of submaps, a global optimization (usually referred 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.
@ -269,7 +269,7 @@ The optimization is run in batches once a certain number of trajectory nodes was
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 sparse pose adjustment fastens those ropes altogether.
The resulting net is called the "*pose graph*".
.. note::
@ -278,7 +278,7 @@ The resulting net is called the "*pose graph*".
- Non-global constraints (also known as intra 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 inter 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).
- Global constraints (also referred to as loop closure constraints or inter submaps constraints) 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
@ -338,7 +338,7 @@ The weights and Ceres options can be configured as described in the :ref:`local-
.. note::
One can find useful information about the residuals used in the optimization problem by toggling ``POSE_GRAPH.max_num_final_iterations``
One can find useful information about the residuals used in the optimization problem by toggling ``POSE_GRAPH.log_residual_histograms``
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.

View File

@ -23,7 +23,6 @@ The Cartographer ROS requirements are the same as `the ones from Cartographer`_.
The following `ROS distributions`_ are currently supported:
* Kinetic
* Melodic
* Noetic
@ -71,8 +70,6 @@ The command 'sudo rosdep init' will print an error if you have already executed
rosdep update
rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y
# Only on Ubuntu 16 / ROS Kinetic: src/cartographer/scripts/install_proto3.sh
Cartographer uses the `abseil-cpp`_ library that needs to be manually installed using this script:
.. code-block:: bash

View File

@ -69,7 +69,7 @@ use_nav_sat
use_landmarks
If enabled, subscribes to `cartographer_ros_msgs/LandmarkList`_ on the topic
"landmarks". Landmarks must be provided, as `cartographer_ros_msgs/LandmarkEntry`_ within `cartographer_ros_msgs/LandmarkList`_. If `cartographer_ros_msgs/LandmarkEntry`_ data is provided the information
will be included in the SLAM accoding to the ID of the `cartographer_ros_msgs/LandmarkEntry`_. The `cartographer_ros_msgs/LandmarkList`_ should be provided at a sample rate comparable to the other sensors. The list can be empty but has to be provided because Cartographer strictly time orders sensor data in order to make the landmarks deterministic. However it is possible to set the trajectory builder option "collate_landmarks" to false and allow for a non-deterministic but also non-blocking approach.
will be included in the SLAM according to the ID of the `cartographer_ros_msgs/LandmarkEntry`_. The `cartographer_ros_msgs/LandmarkList`_ should be provided at a sample rate comparable to the other sensors. The list can be empty but has to be provided because Cartographer strictly time orders sensor data in order to make the landmarks deterministic. However it is possible to set the trajectory builder option "collate_landmarks" to false and allow for a non-deterministic but also non-blocking approach.
num_laser_scans
Number of laser scan topics to subscribe to. Subscribes to
@ -106,7 +106,7 @@ pose_publish_period_sec
publish_to_tf
Enable or disable providing of TF transforms.
publish_tracked_pose_msg
publish_tracked_pose
Enable publishing of tracked pose as a `geometry_msgs/PoseStamped`_ to topic "tracked_pose".
trajectory_publish_period_sec

View File

@ -19,11 +19,7 @@ Getting involved
Cartographer is developed in the open and allows anyone to contribute to the project.
There are multiple ways to get involved!
If you want to stay tuned with announcements (such as new major releases), 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`_.
If you have question or think you've found an issue in Cartographer, you are welcome to open a `GitHub issue`_.
.. _GitHub issue: https://github.com/cartographer-project/cartographer/issues

View File

@ -66,7 +66,7 @@ You can then use Cartographer as part of your calibration process to improve the
Multi-trajectories SLAM
=======================
Cartographer can perform SLAM from multiple robots emiting data in parallel.
Cartographer can perform SLAM from multiple robots emitting 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)

View File

@ -113,7 +113,7 @@ Start by copying one of the provided example:
- ``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.
- ``assets_writer_my_robot.launch`` is used to extract data out of a ``.pbstream`` recording of a previous Cartographer execution.
Again, a few adaptations need to be made to those files to suit your robot.

32
scripts/build_docker.sh Executable file
View File

@ -0,0 +1,32 @@
#!/bin/bash
# Copyright 2016 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.
# Cache intermediate Docker layers. For a description of how this works, see:
# https://giorgos.sealabs.net/docker-cache-on-travis-and-docker-112.html
set -o errexit
set -o verbose
set -o pipefail
if [ "$#" -ne 1 ]; then
echo "Please provide an access token to $0" 1>&2
exit 1
fi
token=$1
CARTOGRAPHER_SHA=$(curl -s -H 'Authorization: token ${token}' https://api.github.com/repos/cartographer-project/cartographer/git/refs/heads/master | jq -j '.object.sha')
docker build ${TRAVIS_BUILD_DIR} -t cartographer_ros:${ROS_RELEASE} -f Dockerfile.${ROS_RELEASE} --build-arg CARTOGRAPHER_SHA=${CARTOGRAPHER_SHA}

View File

@ -34,6 +34,3 @@ cd catkin_ws
# Install rosdep dependencies.
rosdep update
rosdep install --from-paths src --ignore-src --rosdistro=${ROS_DISTRO} -y
# Update rosconsole-bridge to fix build issue with Docker image for Kinetic
sudo apt-get install ros-${ROS_DISTRO}-rosconsole-bridge -y