map_builder_bridge.h
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H
18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H
19 
20 #include <memory>
21 #include <set>
22 #include <string>
23 #include <unordered_map>
24 
27 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
33 #include "cartographer_ros_msgs/SubmapEntry.h"
34 #include "cartographer_ros_msgs/SubmapList.h"
35 #include "cartographer_ros_msgs/SubmapQuery.h"
36 #include "nav_msgs/OccupancyGrid.h"
37 #include "visualization_msgs/MarkerArray.h"
38 
39 namespace cartographer_ros {
40 
42  public:
43  struct TrajectoryState {
44  // Contains the trajectory state data received from local SLAM, after
45  // it had processed accumulated 'range_data_in_local' and estimated
46  // current 'local_pose' at 'time'.
47  struct LocalSlamData {
51  };
52  std::shared_ptr<const LocalSlamData> local_slam_data;
54  std::unique_ptr<cartographer::transform::Rigid3d> published_to_tracking;
56  };
57 
59  const NodeOptions& node_options,
60  std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder,
61  tf2_ros::Buffer* tf_buffer);
62 
63  MapBuilderBridge(const MapBuilderBridge&) = delete;
65 
66  void LoadState(const std::string& state_filename, bool load_frozen_state);
67  int AddTrajectory(
68  const std::set<
70  expected_sensor_ids,
72  void FinishTrajectory(int trajectory_id);
73  void RunFinalOptimization();
74  bool SerializeState(const std::string& filename);
75 
76  void HandleSubmapQuery(
77  cartographer_ros_msgs::SubmapQuery::Request& request,
78  cartographer_ros_msgs::SubmapQuery::Response& response);
79 
80  std::set<int> GetFrozenTrajectoryIds();
81  cartographer_ros_msgs::SubmapList GetSubmapList();
82  std::unordered_map<int, TrajectoryState> GetTrajectoryStates()
83  EXCLUDES(mutex_);
84  visualization_msgs::MarkerArray GetTrajectoryNodeList();
85  visualization_msgs::MarkerArray GetLandmarkPosesList();
86  visualization_msgs::MarkerArray GetConstraintList();
87 
88  SensorBridge* sensor_bridge(int trajectory_id);
89 
90  private:
91  void OnLocalSlamResult(
92  const int trajectory_id, const ::cartographer::common::Time time,
93  const ::cartographer::transform::Rigid3d local_pose,
94  ::cartographer::sensor::RangeData range_data_in_local,
95  const std::unique_ptr<const ::cartographer::mapping::
96  TrajectoryBuilderInterface::InsertionResult>
97  insertion_result) EXCLUDES(mutex_);
98 
99  cartographer::common::Mutex mutex_;
101  std::unordered_map<int, std::shared_ptr<const TrajectoryState::LocalSlamData>>
102  trajectory_state_data_ GUARDED_BY(mutex_);
103  std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder_;
104  tf2_ros::Buffer* const tf_buffer_;
105 
106  std::unordered_map<std::string /* landmark ID */, int> landmark_to_index_;
107 
108  // These are keyed with 'trajectory_id'.
110  std::unordered_map<int, std::unique_ptr<SensorBridge>> sensor_bridges_;
111  std::unordered_map<int, size_t> trajectory_to_highest_marker_id_;
112 };
113 
114 } // namespace cartographer_ros
115 
116 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H
std::unordered_map< int, size_t > trajectory_to_highest_marker_id_
visualization_msgs::MarkerArray GetTrajectoryNodeList()
visualization_msgs::MarkerArray GetConstraintList()
void HandleSubmapQuery(cartographer_ros_msgs::SubmapQuery::Request &request, cartographer_ros_msgs::SubmapQuery::Response &response)
cartographer::common::Mutex mutex_
std::unordered_map< int, std::shared_ptr< const TrajectoryState::LocalSlamData > > trajectory_state_data_ GUARDED_BY(mutex_)
std::unordered_map< int, TrajectoryState > GetTrajectoryStates() EXCLUDES(mutex_)
std::unordered_map< std::string, int > landmark_to_index_
SensorBridge * sensor_bridge(int trajectory_id)
UniversalTimeScaleClock::time_point Time
visualization_msgs::MarkerArray GetLandmarkPosesList()
void FinishTrajectory(int trajectory_id)
cartographer_ros_msgs::SubmapList GetSubmapList()
void LoadState(const std::string &state_filename, bool load_frozen_state)
MapBuilderBridge & operator=(const MapBuilderBridge &)=delete
int AddTrajectory(const std::set< ::cartographer::mapping::TrajectoryBuilderInterface::SensorId > &expected_sensor_ids, const TrajectoryOptions &trajectory_options)
bool SerializeState(const std::string &filename)
std::shared_ptr< const LocalSlamData > local_slam_data
std::unique_ptr< cartographer::mapping::MapBuilderInterface > map_builder_
std::unique_ptr< cartographer::transform::Rigid3d > published_to_tracking
std::unordered_map< int, TrajectoryOptions > trajectory_options_
void OnLocalSlamResult(const int trajectory_id, const ::cartographer::common::Time time, const ::cartographer::transform::Rigid3d local_pose, ::cartographer::sensor::RangeData range_data_in_local, const std::unique_ptr< const ::cartographer::mapping::TrajectoryBuilderInterface::InsertionResult > insertion_result) EXCLUDES(mutex_)
MapBuilderBridge(const NodeOptions &node_options, std::unique_ptr< cartographer::mapping::MapBuilderInterface > map_builder, tf2_ros::Buffer *tf_buffer)
std::unordered_map< int, std::unique_ptr< SensorBridge > > sensor_bridges_


cartographer_ros
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:06:05