map_builder_bridge.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 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_ROS_CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H
00018 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H
00019 
00020 #include <memory>
00021 #include <set>
00022 #include <string>
00023 #include <unordered_map>
00024 
00025 #include "absl/synchronization/mutex.h"
00026 #include "cartographer/mapping/map_builder_interface.h"
00027 #include "cartographer/mapping/pose_graph_interface.h"
00028 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
00029 #include "cartographer/mapping/trajectory_builder_interface.h"
00030 #include "cartographer_ros/node_options.h"
00031 #include "cartographer_ros/sensor_bridge.h"
00032 #include "cartographer_ros/tf_bridge.h"
00033 #include "cartographer_ros/trajectory_options.h"
00034 #include "cartographer_ros_msgs/SubmapEntry.h"
00035 #include "cartographer_ros_msgs/SubmapList.h"
00036 #include "cartographer_ros_msgs/SubmapQuery.h"
00037 #include "cartographer_ros_msgs/TrajectoryQuery.h"
00038 #include "geometry_msgs/TransformStamped.h"
00039 #include "nav_msgs/OccupancyGrid.h"
00040 
00041 // Abseil unfortunately pulls in winnt.h, which #defines DELETE.
00042 // Clean up to unbreak visualization_msgs::Marker::DELETE.
00043 #ifdef DELETE
00044 #undef DELETE
00045 #endif
00046 #include "visualization_msgs/MarkerArray.h"
00047 
00048 namespace cartographer_ros {
00049 
00050 class MapBuilderBridge {
00051  public:
00052   struct LocalTrajectoryData {
00053     // Contains the trajectory data received from local SLAM, after
00054     // it had processed accumulated 'range_data_in_local' and estimated
00055     // current 'local_pose' at 'time'.
00056     struct LocalSlamData {
00057       ::cartographer::common::Time time;
00058       ::cartographer::transform::Rigid3d local_pose;
00059       ::cartographer::sensor::RangeData range_data_in_local;
00060     };
00061     std::shared_ptr<const LocalSlamData> local_slam_data;
00062     cartographer::transform::Rigid3d local_to_map;
00063     std::unique_ptr<cartographer::transform::Rigid3d> published_to_tracking;
00064     TrajectoryOptions trajectory_options;
00065   };
00066 
00067   MapBuilderBridge(
00068       const NodeOptions& node_options,
00069       std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder,
00070       tf2_ros::Buffer* tf_buffer);
00071 
00072   MapBuilderBridge(const MapBuilderBridge&) = delete;
00073   MapBuilderBridge& operator=(const MapBuilderBridge&) = delete;
00074 
00075   void LoadState(const std::string& state_filename, bool load_frozen_state);
00076   int AddTrajectory(
00077       const std::set<
00078           ::cartographer::mapping::TrajectoryBuilderInterface::SensorId>&
00079           expected_sensor_ids,
00080       const TrajectoryOptions& trajectory_options);
00081   void FinishTrajectory(int trajectory_id);
00082   void RunFinalOptimization();
00083   bool SerializeState(const std::string& filename,
00084                       const bool include_unfinished_submaps);
00085 
00086   void HandleSubmapQuery(
00087       cartographer_ros_msgs::SubmapQuery::Request& request,
00088       cartographer_ros_msgs::SubmapQuery::Response& response);
00089   void HandleTrajectoryQuery(
00090       cartographer_ros_msgs::TrajectoryQuery::Request& request,
00091       cartographer_ros_msgs::TrajectoryQuery::Response& response);
00092 
00093   std::map<int /* trajectory_id */,
00094            ::cartographer::mapping::PoseGraphInterface::TrajectoryState>
00095   GetTrajectoryStates();
00096   cartographer_ros_msgs::SubmapList GetSubmapList();
00097   std::unordered_map<int, LocalTrajectoryData> GetLocalTrajectoryData()
00098       LOCKS_EXCLUDED(mutex_);
00099   visualization_msgs::MarkerArray GetTrajectoryNodeList();
00100   visualization_msgs::MarkerArray GetLandmarkPosesList();
00101   visualization_msgs::MarkerArray GetConstraintList();
00102 
00103   SensorBridge* sensor_bridge(int trajectory_id);
00104 
00105  private:
00106   void OnLocalSlamResult(const int trajectory_id,
00107                          const ::cartographer::common::Time time,
00108                          const ::cartographer::transform::Rigid3d local_pose,
00109                          ::cartographer::sensor::RangeData range_data_in_local)
00110       LOCKS_EXCLUDED(mutex_);
00111 
00112   absl::Mutex mutex_;
00113   const NodeOptions node_options_;
00114   std::unordered_map<int,
00115                      std::shared_ptr<const LocalTrajectoryData::LocalSlamData>>
00116       local_slam_data_ GUARDED_BY(mutex_);
00117   std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder_;
00118   tf2_ros::Buffer* const tf_buffer_;
00119 
00120   std::unordered_map<std::string /* landmark ID */, int> landmark_to_index_;
00121 
00122   // These are keyed with 'trajectory_id'.
00123   std::unordered_map<int, TrajectoryOptions> trajectory_options_;
00124   std::unordered_map<int, std::unique_ptr<SensorBridge>> sensor_bridges_;
00125   std::unordered_map<int, size_t> trajectory_to_highest_marker_id_;
00126 };
00127 
00128 }  // namespace cartographer_ros
00129 
00130 #endif  // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Wed Jul 10 2019 04:10:28