node.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_NODE_H
18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_NODE_H
19 
20 #include <map>
21 #include <memory>
22 #include <set>
23 #include <unordered_map>
24 #include <unordered_set>
25 #include <vector>
26 
35 #include "cartographer_ros_msgs/FinishTrajectory.h"
36 #include "cartographer_ros_msgs/SensorTopics.h"
37 #include "cartographer_ros_msgs/StartTrajectory.h"
38 #include "cartographer_ros_msgs/StatusResponse.h"
39 #include "cartographer_ros_msgs/SubmapEntry.h"
40 #include "cartographer_ros_msgs/SubmapList.h"
41 #include "cartographer_ros_msgs/SubmapQuery.h"
42 #include "cartographer_ros_msgs/TrajectoryOptions.h"
43 #include "cartographer_ros_msgs/WriteState.h"
44 #include "nav_msgs/Odometry.h"
45 #include "ros/ros.h"
46 #include "sensor_msgs/Imu.h"
47 #include "sensor_msgs/LaserScan.h"
48 #include "sensor_msgs/MultiEchoLaserScan.h"
49 #include "sensor_msgs/NavSatFix.h"
50 #include "sensor_msgs/PointCloud2.h"
52 
53 namespace cartographer_ros {
54 
55 // Wires up ROS topics to SLAM.
56 class Node {
57  public:
58  Node(const NodeOptions& node_options,
59  std::unique_ptr<cartographer::mapping::MapBuilderInterface> map_builder,
61  ~Node();
62 
63  Node(const Node&) = delete;
64  Node& operator=(const Node&) = delete;
65 
66  // Finishes all yet active trajectories.
67  void FinishAllTrajectories();
68  // Finishes a single given trajectory. Returns false if the trajectory did not
69  // exist or was already finished.
70  bool FinishTrajectory(int trajectory_id);
71 
72  // Runs final optimization. All trajectories have to be finished when calling.
73  void RunFinalOptimization();
74 
75  // Starts the first trajectory with the default topics.
77 
78  // Returns unique SensorIds for multiple input bag files based on
79  // their TrajectoryOptions.
80  // 'SensorId::id' is the expected ROS topic name.
81  std::vector<
82  std::set<::cartographer::mapping::TrajectoryBuilderInterface::SensorId>>
84  const std::vector<TrajectoryOptions>& bags_options) const;
85 
86  // Adds a trajectory for offline processing, i.e. not listening to topics.
88  const std::set<
90  expected_sensor_ids,
91  const TrajectoryOptions& options);
92 
93  // The following functions handle adding sensor data to a trajectory.
94  void HandleOdometryMessage(int trajectory_id, const std::string& sensor_id,
95  const nav_msgs::Odometry::ConstPtr& msg);
96  void HandleNavSatFixMessage(int trajectory_id, const std::string& sensor_id,
97  const sensor_msgs::NavSatFix::ConstPtr& msg);
99  int trajectory_id, const std::string& sensor_id,
100  const cartographer_ros_msgs::LandmarkList::ConstPtr& msg);
101  void HandleImuMessage(int trajectory_id, const std::string& sensor_id,
102  const sensor_msgs::Imu::ConstPtr& msg);
103  void HandleLaserScanMessage(int trajectory_id, const std::string& sensor_id,
104  const sensor_msgs::LaserScan::ConstPtr& msg);
106  int trajectory_id, const std::string& sensor_id,
107  const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg);
108  void HandlePointCloud2Message(int trajectory_id, const std::string& sensor_id,
109  const sensor_msgs::PointCloud2::ConstPtr& msg);
110 
111  // Serializes the complete Node state.
112  void SerializeState(const std::string& filename);
113 
114  // Loads a serialized SLAM state from a .pbstream file.
115  void LoadState(const std::string& state_filename, bool load_frozen_state);
116 
118 
119  private:
120  struct Subscriber {
122 
123  // ::ros::Subscriber::getTopic() does not necessarily return the same
124  // std::string
125  // it was given in its constructor. Since we rely on the topic name as the
126  // unique identifier of a subscriber, we remember it ourselves.
127  std::string topic;
128  };
129 
130  bool HandleSubmapQuery(
131  cartographer_ros_msgs::SubmapQuery::Request& request,
132  cartographer_ros_msgs::SubmapQuery::Response& response);
134  cartographer_ros_msgs::StartTrajectory::Request& request,
135  cartographer_ros_msgs::StartTrajectory::Response& response);
137  cartographer_ros_msgs::FinishTrajectory::Request& request,
138  cartographer_ros_msgs::FinishTrajectory::Response& response);
139  bool HandleWriteState(cartographer_ros_msgs::WriteState::Request& request,
140  cartographer_ros_msgs::WriteState::Response& response);
141  // Returns the set of SensorIds expected for a trajectory.
142  // 'SensorId::id' is the expected ROS topic name.
143  std::set<::cartographer::mapping::TrajectoryBuilderInterface::SensorId>
145  const TrajectoryOptions& options,
146  const cartographer_ros_msgs::SensorTopics& topics) const;
147  int AddTrajectory(const TrajectoryOptions& options,
148  const cartographer_ros_msgs::SensorTopics& topics);
149  void LaunchSubscribers(const TrajectoryOptions& options,
150  const cartographer_ros_msgs::SensorTopics& topics,
151  int trajectory_id);
152  void PublishSubmapList(const ::ros::WallTimerEvent& timer_event);
153  void AddExtrapolator(int trajectory_id, const TrajectoryOptions& options);
154  void AddSensorSamplers(int trajectory_id, const TrajectoryOptions& options);
155  void PublishTrajectoryStates(const ::ros::WallTimerEvent& timer_event);
156  void PublishTrajectoryNodeList(const ::ros::WallTimerEvent& timer_event);
157  void PublishLandmarkPosesList(const ::ros::WallTimerEvent& timer_event);
158  void PublishConstraintList(const ::ros::WallTimerEvent& timer_event);
160  bool ValidateTrajectoryOptions(const TrajectoryOptions& options);
161  bool ValidateTopicNames(const ::cartographer_ros_msgs::SensorTopics& topics,
162  const TrajectoryOptions& options);
163  cartographer_ros_msgs::StatusResponse FinishTrajectoryUnderLock(
164  int trajectory_id) REQUIRES(mutex_);
165 
167 
169 
170  cartographer::common::Mutex mutex_;
171  MapBuilderBridge map_builder_bridge_ GUARDED_BY(mutex_);
172 
178  // These ros::ServiceServers need to live for the lifetime of the node.
179  std::vector<::ros::ServiceServer> service_servers_;
181 
183  TrajectorySensorSamplers(const double rangefinder_sampling_ratio,
184  const double odometry_sampling_ratio,
185  const double fixed_frame_pose_sampling_ratio,
186  const double imu_sampling_ratio,
187  const double landmark_sampling_ratio)
188  : rangefinder_sampler(rangefinder_sampling_ratio),
189  odometry_sampler(odometry_sampling_ratio),
190  fixed_frame_pose_sampler(fixed_frame_pose_sampling_ratio),
191  imu_sampler(imu_sampling_ratio),
192  landmark_sampler(landmark_sampling_ratio) {}
193 
199  };
200 
201  // These are keyed with 'trajectory_id'.
202  std::map<int, ::cartographer::mapping::PoseExtrapolator> extrapolators_;
203  std::unordered_map<int, TrajectorySensorSamplers> sensor_samplers_;
204  std::unordered_map<int, std::vector<Subscriber>> subscribers_;
205  std::unordered_set<std::string> subscribed_topics_;
206  std::unordered_map<int, bool> is_active_trajectory_ GUARDED_BY(mutex_);
207 
208  // We have to keep the timer handles of ::ros::WallTimers around, otherwise
209  // they do not fire.
210  std::vector<::ros::WallTimer> wall_timers_;
211 };
212 
213 } // namespace cartographer_ros
214 
215 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_NODE_H
bool FinishTrajectory(int trajectory_id)
Definition: node.cc:590
::ros::Publisher trajectory_node_list_publisher_
Definition: node.h:175
Node & operator=(const Node &)=delete
filename
void SerializeState(const std::string &filename)
Definition: node.cc:693
::cartographer::common::FixedRatioSampler landmark_sampler
Definition: node.h:198
std::vector<::ros::ServiceServer > service_servers_
Definition: node.h:179
void FinishAllTrajectories()
Definition: node.cc:579
std::vector< std::set<::cartographer::mapping::TrajectoryBuilderInterface::SensorId > > ComputeDefaultSensorIdsForMultipleBags(const std::vector< TrajectoryOptions > &bags_options) const
Definition: node.cc:525
::ros::Publisher landmark_poses_list_publisher_
Definition: node.h:176
void HandleMultiEchoLaserScanMessage(int trajectory_id, const std::string &sensor_id, const sensor_msgs::MultiEchoLaserScan::ConstPtr &msg)
Definition: node.cc:671
::cartographer::common::FixedRatioSampler fixed_frame_pose_sampler
Definition: node.h:196
bool ValidateTrajectoryOptions(const TrajectoryOptions &options)
Definition: node.cc:420
std::unordered_map< int, TrajectorySensorSamplers > sensor_samplers_
Definition: node.h:203
void PublishSubmapList(const ::ros::WallTimerEvent &timer_event)
Definition: node.cc:146
int AddOfflineTrajectory(const std::set< cartographer::mapping::TrajectoryBuilderInterface::SensorId > &expected_sensor_ids, const TrajectoryOptions &options)
Definition: node.cc:544
Node(const NodeOptions &node_options, std::unique_ptr< cartographer::mapping::MapBuilderInterface > map_builder, tf2_ros::Buffer *tf_buffer)
Definition: node.cc:85
cartographer::common::Mutex mutex_
Definition: node.h:170
const NodeOptions node_options_
Definition: node.h:166
tf2_ros::TransformBroadcaster tf_broadcaster_
Definition: node.h:168
void AddExtrapolator(int trajectory_id, const TrajectoryOptions &options)
Definition: node.cc:151
bool HandleStartTrajectory(cartographer_ros_msgs::StartTrajectory::Request &request, cartographer_ros_msgs::StartTrajectory::Response &response)
Definition: node.cc:493
::ros::Publisher scan_matched_point_cloud_publisher_
Definition: node.h:180
void PublishTrajectoryNodeList(const ::ros::WallTimerEvent &timer_event)
Definition: node.cc:263
void RunFinalOptimization()
Definition: node.cc:596
TrajectorySensorSamplers(const double rangefinder_sampling_ratio, const double odometry_sampling_ratio, const double fixed_frame_pose_sampling_ratio, const double imu_sampling_ratio, const double landmark_sampling_ratio)
Definition: node.h:183
void SpinOccupancyGridThreadForever()
::ros::Publisher submap_list_publisher_
Definition: node.h:174
void HandlePointCloud2Message(int trajectory_id, const std::string &sensor_id, const sensor_msgs::PointCloud2::ConstPtr &msg)
Definition: node.cc:682
cartographer_ros_msgs::StatusResponse FinishTrajectoryUnderLock(int trajectory_id) REQUIRES(mutex_)
Definition: node.cc:445
void HandleOdometryMessage(int trajectory_id, const std::string &sensor_id, const nav_msgs::Odometry::ConstPtr &msg)
Definition: node.cc:608
void HandleImuMessage(int trajectory_id, const std::string &sensor_id, const sensor_msgs::Imu::ConstPtr &msg)
Definition: node.cc:645
options
#define REQUIRES(...)
void HandleLaserScanMessage(int trajectory_id, const std::string &sensor_id, const sensor_msgs::LaserScan::ConstPtr &msg)
Definition: node.cc:660
::ros::Publisher constraint_list_publisher_
Definition: node.h:177
::ros::NodeHandle node_handle_
Definition: node.h:173
std::vector<::ros::WallTimer > wall_timers_
Definition: node.h:210
int AddTrajectory(const TrajectoryOptions &options, const cartographer_ros_msgs::SensorTopics &topics)
Definition: node.cc:335
MapBuilderBridge map_builder_bridge_ GUARDED_BY(mutex_)
void HandleNavSatFixMessage(int trajectory_id, const std::string &sensor_id, const sensor_msgs::NavSatFix::ConstPtr &msg)
Definition: node.cc:623
void PublishConstraintList(const ::ros::WallTimerEvent &timer_event)
Definition: node.cc:281
void LoadState(const std::string &state_filename, bool load_frozen_state)
Definition: node.cc:699
std::unordered_set< std::string > subscribed_topics_
Definition: node.h:205
void AddSensorSamplers(int trajectory_id, const TrajectoryOptions &options)
Definition: node.cc:168
::ros::NodeHandle * node_handle()
Definition: node.cc:136
::cartographer::common::FixedRatioSampler imu_sampler
Definition: node.h:197
bool HandleFinishTrajectory(cartographer_ros_msgs::FinishTrajectory::Request &request, cartographer_ros_msgs::FinishTrajectory::Response &response)
Definition: node.cc:557
void StartTrajectoryWithDefaultTopics(const TrajectoryOptions &options)
Definition: node.cc:517
::cartographer::common::FixedRatioSampler odometry_sampler
Definition: node.h:195
std::unordered_map< int, std::vector< Subscriber > > subscribers_
Definition: node.h:204
bool HandleWriteState(cartographer_ros_msgs::WriteState::Request &request, cartographer_ros_msgs::WriteState::Response &response)
Definition: node.cc:565
std::map< int, ::cartographer::mapping::PoseExtrapolator > extrapolators_
Definition: node.h:202
void HandleLandmarkMessage(int trajectory_id, const std::string &sensor_id, const cartographer_ros_msgs::LandmarkList::ConstPtr &msg)
Definition: node.cc:634
::ros::Subscriber subscriber
Definition: node.h:121
bool HandleSubmapQuery(cartographer_ros_msgs::SubmapQuery::Request &request, cartographer_ros_msgs::SubmapQuery::Response &response)
Definition: node.cc:138
void LaunchSubscribers(const TrajectoryOptions &options, const cartographer_ros_msgs::SensorTopics &topics, int trajectory_id)
Definition: node.cc:351
bool ValidateTopicNames(const ::cartographer_ros_msgs::SensorTopics &topics, const TrajectoryOptions &options)
Definition: node.cc:432
::cartographer::common::FixedRatioSampler rangefinder_sampler
Definition: node.h:194
tf2_ros::Buffer * tf_buffer
void PublishTrajectoryStates(const ::ros::WallTimerEvent &timer_event)
Definition: node.cc:179
void PublishLandmarkPosesList(const ::ros::WallTimerEvent &timer_event)
Definition: node.cc:272
std::set<::cartographer::mapping::TrajectoryBuilderInterface::SensorId > ComputeExpectedSensorIds(const TrajectoryOptions &options, const cartographer_ros_msgs::SensorTopics &topics) const
Definition: node.cc:290


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