optimization_problem_interface.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2018 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_OPTIMIZATION_PROBLEM_INTERFACE_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_OPTIMIZATION_PROBLEM_INTERFACE_H_
00019 
00020 #include <map>
00021 #include <set>
00022 #include <vector>
00023 
00024 #include "Eigen/Core"
00025 #include "Eigen/Geometry"
00026 #include "cartographer/common/time.h"
00027 #include "cartographer/mapping/id.h"
00028 #include "cartographer/mapping/pose_graph_interface.h"
00029 #include "cartographer/sensor/fixed_frame_pose_data.h"
00030 #include "cartographer/sensor/imu_data.h"
00031 #include "cartographer/sensor/map_by_time.h"
00032 #include "cartographer/sensor/odometry_data.h"
00033 
00034 namespace cartographer {
00035 namespace mapping {
00036 namespace optimization {
00037 
00038 // Implements the SPA loop closure method.
00039 template <typename NodeDataType, typename SubmapDataType,
00040           typename RigidTransformType>
00041 class OptimizationProblemInterface {
00042  public:
00043   using Constraint = PoseGraphInterface::Constraint;
00044   using LandmarkNode = PoseGraphInterface::LandmarkNode;
00045 
00046   OptimizationProblemInterface() {}
00047   virtual ~OptimizationProblemInterface() {}
00048 
00049   OptimizationProblemInterface(const OptimizationProblemInterface&) = delete;
00050   OptimizationProblemInterface& operator=(const OptimizationProblemInterface&) =
00051       delete;
00052 
00053   virtual void AddImuData(int trajectory_id,
00054                           const sensor::ImuData& imu_data) = 0;
00055   virtual void AddOdometryData(int trajectory_id,
00056                                const sensor::OdometryData& odometry_data) = 0;
00057   virtual void AddTrajectoryNode(int trajectory_id,
00058                                  const NodeDataType& node_data) = 0;
00059   virtual void InsertTrajectoryNode(const NodeId& node_id,
00060                                     const NodeDataType& node_data) = 0;
00061   virtual void TrimTrajectoryNode(const NodeId& node_id) = 0;
00062   virtual void AddSubmap(int trajectory_id,
00063                          const RigidTransformType& global_submap_pose) = 0;
00064   virtual void InsertSubmap(const SubmapId& submap_id,
00065                             const RigidTransformType& global_submap_pose) = 0;
00066   virtual void TrimSubmap(const SubmapId& submap_id) = 0;
00067   virtual void SetMaxNumIterations(int32 max_num_iterations) = 0;
00068 
00069   // Optimizes the global poses.
00070   virtual void Solve(
00071       const std::vector<Constraint>& constraints,
00072       const std::map<int, PoseGraphInterface::TrajectoryState>&
00073           trajectories_state,
00074       const std::map<std::string, LandmarkNode>& landmark_nodes) = 0;
00075 
00076   virtual const MapById<NodeId, NodeDataType>& node_data() const = 0;
00077   virtual const MapById<SubmapId, SubmapDataType>& submap_data() const = 0;
00078   virtual const std::map<std::string, transform::Rigid3d>& landmark_data()
00079       const = 0;
00080   virtual const sensor::MapByTime<sensor::ImuData>& imu_data() const = 0;
00081   virtual const sensor::MapByTime<sensor::OdometryData>& odometry_data()
00082       const = 0;
00083 };
00084 
00085 }  // namespace optimization
00086 }  // namespace mapping
00087 }  // namespace cartographer
00088 
00089 #endif  // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_OPTIMIZATION_PROBLEM_INTERFACE_H_


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35