Forward declare unique_ptr<LocalSlamResultData> (#824)

master
Christoph Schütte 2018-01-16 10:20:51 +01:00 committed by Wally B. Feed
parent c053fc7a2f
commit 3660408ae6
3 changed files with 4 additions and 1 deletions

View File

@ -25,6 +25,7 @@
#include "cartographer/common/port.h" #include "cartographer/common/port.h"
#include "cartographer/common/rate_timer.h" #include "cartographer/common/rate_timer.h"
#include "cartographer/mapping/local_slam_result_data.h"
#include "cartographer/mapping/submaps.h" #include "cartographer/mapping/submaps.h"
#include "cartographer/mapping/trajectory_builder_interface.h" #include "cartographer/mapping/trajectory_builder_interface.h"
#include "cartographer/sensor/collator_interface.h" #include "cartographer/sensor/collator_interface.h"

View File

@ -16,6 +16,7 @@
#include "cartographer/mapping/trajectory_builder_interface.h" #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_2d/local_trajectory_builder_options.h"
#include "cartographer/mapping_3d/local_trajectory_builder_options.h" #include "cartographer/mapping_3d/local_trajectory_builder_options.h"

View File

@ -25,7 +25,6 @@
#include "cartographer/common/make_unique.h" #include "cartographer/common/make_unique.h"
#include "cartographer/common/port.h" #include "cartographer/common/port.h"
#include "cartographer/common/time.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/proto/trajectory_builder_options.pb.h"
#include "cartographer/mapping/submaps.h" #include "cartographer/mapping/submaps.h"
#include "cartographer/sensor/fixed_frame_pose_data.h" #include "cartographer/sensor/fixed_frame_pose_data.h"
@ -39,6 +38,8 @@ namespace mapping {
proto::TrajectoryBuilderOptions CreateTrajectoryBuilderOptions( proto::TrajectoryBuilderOptions CreateTrajectoryBuilderOptions(
common::LuaParameterDictionary* const parameter_dictionary); common::LuaParameterDictionary* const parameter_dictionary);
class LocalSlamResultData;
// This interface is used for both 2D and 3D SLAM. Implementations wire up a // 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 // 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 // to detect loop closure, and a sparse pose graph optimization to compute