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_MAP_BUILDER_BRIDGE_H_
18 #define CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H_
19 
20 #include <memory>
21 #include <unordered_map>
22 #include <unordered_set>
23 
25 #include "cartographer/mapping/proto/trajectory_builder_options.pb.h"
30 #include "cartographer_ros_msgs/SubmapEntry.h"
31 #include "cartographer_ros_msgs/SubmapList.h"
32 #include "cartographer_ros_msgs/SubmapQuery.h"
33 #include "nav_msgs/OccupancyGrid.h"
34 #include "visualization_msgs/MarkerArray.h"
35 
36 namespace cartographer_ros {
37 
39  public:
40  struct TrajectoryState {
41  cartographer::mapping::TrajectoryBuilder::PoseEstimate pose_estimate;
43  std::unique_ptr<cartographer::transform::Rigid3d> published_to_tracking;
45  };
46 
47  MapBuilderBridge(const NodeOptions& node_options, tf2_ros::Buffer* tf_buffer);
48 
49  MapBuilderBridge(const MapBuilderBridge&) = delete;
51 
52  int AddTrajectory(const std::unordered_set<string>& expected_sensor_ids,
54  void FinishTrajectory(int trajectory_id);
55  void SerializeState(const string& stem);
56  void WriteAssets(const string& stem);
57 
58  bool HandleSubmapQuery(
59  cartographer_ros_msgs::SubmapQuery::Request& request,
60  cartographer_ros_msgs::SubmapQuery::Response& response);
61 
62  cartographer_ros_msgs::SubmapList GetSubmapList();
63  std::unique_ptr<nav_msgs::OccupancyGrid> BuildOccupancyGrid();
64  std::unordered_map<int, TrajectoryState> GetTrajectoryStates();
65  visualization_msgs::MarkerArray GetTrajectoryNodesList();
66 
67  SensorBridge* sensor_bridge(int trajectory_id);
68 
69  private:
73 
74  // These are keyed with 'trajectory_id'.
75  std::unordered_map<int, TrajectoryOptions> trajectory_options_;
76  std::unordered_map<int, std::unique_ptr<SensorBridge>> sensor_bridges_;
77 };
78 
79 } // namespace cartographer_ros
80 
81 #endif // CARTOGRAPHER_ROS_MAP_BUILDER_BRIDGE_H_
void WriteAssets(const string &stem)
cartographer::mapping::TrajectoryBuilder::PoseEstimate pose_estimate
SensorBridge * sensor_bridge(int trajectory_id)
void FinishTrajectory(int trajectory_id)
cartographer::mapping::MapBuilder map_builder_
visualization_msgs::MarkerArray GetTrajectoryNodesList()
cartographer_ros_msgs::SubmapList GetSubmapList()
void SerializeState(const string &stem)
MapBuilderBridge & operator=(const MapBuilderBridge &)=delete
MapBuilderBridge(const NodeOptions &node_options, tf2_ros::Buffer *tf_buffer)
std::unique_ptr< cartographer::transform::Rigid3d > published_to_tracking
bool HandleSubmapQuery(cartographer_ros_msgs::SubmapQuery::Request &request, cartographer_ros_msgs::SubmapQuery::Response &response)
std::unordered_map< int, TrajectoryOptions > trajectory_options_
std::unordered_map< int, TrajectoryState > GetTrajectoryStates()
int AddTrajectory(const std::unordered_set< string > &expected_sensor_ids, const TrajectoryOptions &trajectory_options)
std::unique_ptr< nav_msgs::OccupancyGrid > BuildOccupancyGrid()
std::unordered_map< int, std::unique_ptr< SensorBridge > > sensor_bridges_


cartographer_ros
Author(s):
autogenerated on Mon Jun 10 2019 12:59:40