From 3660408ae615226fc85888e28fa0a236e72ab5fc Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Sch=C3=BCtte?= Date: Tue, 16 Jan 2018 10:20:51 +0100 Subject: [PATCH] Forward declare unique_ptr (#824) --- cartographer/mapping/collated_trajectory_builder.h | 1 + cartographer/mapping/trajectory_builder_interface.cc | 1 + cartographer/mapping/trajectory_builder_interface.h | 3 ++- 3 files changed, 4 insertions(+), 1 deletion(-) diff --git a/cartographer/mapping/collated_trajectory_builder.h b/cartographer/mapping/collated_trajectory_builder.h index 389546a..407b882 100644 --- a/cartographer/mapping/collated_trajectory_builder.h +++ b/cartographer/mapping/collated_trajectory_builder.h @@ -25,6 +25,7 @@ #include "cartographer/common/port.h" #include "cartographer/common/rate_timer.h" +#include "cartographer/mapping/local_slam_result_data.h" #include "cartographer/mapping/submaps.h" #include "cartographer/mapping/trajectory_builder_interface.h" #include "cartographer/sensor/collator_interface.h" diff --git a/cartographer/mapping/trajectory_builder_interface.cc b/cartographer/mapping/trajectory_builder_interface.cc index b412402..0c3cc35 100644 --- a/cartographer/mapping/trajectory_builder_interface.cc +++ b/cartographer/mapping/trajectory_builder_interface.cc @@ -16,6 +16,7 @@ #include "cartographer/mapping/trajectory_builder_interface.h" +#include "cartographer/mapping/local_slam_result_data.h" #include "cartographer/mapping_2d/local_trajectory_builder_options.h" #include "cartographer/mapping_3d/local_trajectory_builder_options.h" diff --git a/cartographer/mapping/trajectory_builder_interface.h b/cartographer/mapping/trajectory_builder_interface.h index fd2e3a1..8a5d912 100644 --- a/cartographer/mapping/trajectory_builder_interface.h +++ b/cartographer/mapping/trajectory_builder_interface.h @@ -25,7 +25,6 @@ #include "cartographer/common/make_unique.h" #include "cartographer/common/port.h" #include "cartographer/common/time.h" -#include "cartographer/mapping/local_slam_result_data.h" #include "cartographer/mapping/proto/trajectory_builder_options.pb.h" #include "cartographer/mapping/submaps.h" #include "cartographer/sensor/fixed_frame_pose_data.h" @@ -39,6 +38,8 @@ namespace mapping { proto::TrajectoryBuilderOptions CreateTrajectoryBuilderOptions( common::LuaParameterDictionary* const parameter_dictionary); +class LocalSlamResultData; + // This interface is used for both 2D and 3D SLAM. Implementations wire up a // global SLAM stack, i.e. local SLAM for initial pose estimates, scan matching // to detect loop closure, and a sparse pose graph optimization to compute