sensor_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_SENSOR_BRIDGE_H
18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_SENSOR_BRIDGE_H
19 
20 #include <memory>
21 
29 #include "cartographer_ros_msgs/LandmarkList.h"
30 #include "geometry_msgs/Transform.h"
31 #include "geometry_msgs/TransformStamped.h"
32 #include "nav_msgs/OccupancyGrid.h"
33 #include "nav_msgs/Odometry.h"
34 #include "sensor_msgs/Imu.h"
35 #include "sensor_msgs/LaserScan.h"
36 #include "sensor_msgs/MultiEchoLaserScan.h"
37 #include "sensor_msgs/NavSatFix.h"
38 #include "sensor_msgs/PointCloud2.h"
39 
40 namespace cartographer_ros {
41 
42 // Converts ROS messages into SensorData in tracking frame for the MapBuilder.
43 class SensorBridge {
44  public:
45  explicit SensorBridge(
46  int num_subdivisions_per_laser_scan, const std::string& tracking_frame,
47  double lookup_transform_timeout_sec, tf2_ros::Buffer* tf_buffer,
49 
50  SensorBridge(const SensorBridge&) = delete;
51  SensorBridge& operator=(const SensorBridge&) = delete;
52 
53  std::unique_ptr<::cartographer::sensor::OdometryData> ToOdometryData(
54  const nav_msgs::Odometry::ConstPtr& msg);
55  void HandleOdometryMessage(const std::string& sensor_id,
56  const nav_msgs::Odometry::ConstPtr& msg);
57  void HandleNavSatFixMessage(const std::string& sensor_id,
58  const sensor_msgs::NavSatFix::ConstPtr& msg);
60  const std::string& sensor_id,
61  const cartographer_ros_msgs::LandmarkList::ConstPtr& msg);
62 
63  std::unique_ptr<::cartographer::sensor::ImuData> ToImuData(
64  const sensor_msgs::Imu::ConstPtr& msg);
65  void HandleImuMessage(const std::string& sensor_id,
66  const sensor_msgs::Imu::ConstPtr& msg);
67  void HandleLaserScanMessage(const std::string& sensor_id,
68  const sensor_msgs::LaserScan::ConstPtr& msg);
70  const std::string& sensor_id,
71  const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg);
72  void HandlePointCloud2Message(const std::string& sensor_id,
73  const sensor_msgs::PointCloud2::ConstPtr& msg);
74 
75  const TfBridge& tf_bridge() const;
76 
77  private:
78  void HandleLaserScan(
79  const std::string& sensor_id, ::cartographer::common::Time start_time,
80  const std::string& frame_id,
81  const ::cartographer::sensor::PointCloudWithIntensities& points);
82  void HandleRangefinder(const std::string& sensor_id,
84  const std::string& frame_id,
85  const ::cartographer::sensor::TimedPointCloud& ranges);
86 
88  std::map<std::string, cartographer::common::Time>
93 
96 };
97 
98 } // namespace cartographer_ros
99 
100 #endif // CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_SENSOR_BRIDGE_H
void HandleRangefinder(const std::string &sensor_id, ::cartographer::common::Time time, const std::string &frame_id, const ::cartographer::sensor::TimedPointCloud &ranges)
SensorBridge & operator=(const SensorBridge &)=delete
void HandleImuMessage(const std::string &sensor_id, const sensor_msgs::Imu::ConstPtr &msg)
std::unique_ptr<::cartographer::sensor::ImuData > ToImuData(const sensor_msgs::Imu::ConstPtr &msg)
void HandleMultiEchoLaserScanMessage(const std::string &sensor_id, const sensor_msgs::MultiEchoLaserScan::ConstPtr &msg)
const common::Time time
SensorBridge(int num_subdivisions_per_laser_scan, const std::string &tracking_frame, double lookup_transform_timeout_sec, tf2_ros::Buffer *tf_buffer, ::cartographer::mapping::TrajectoryBuilderInterface *trajectory_builder)
std::unique_ptr<::cartographer::sensor::OdometryData > ToOdometryData(const nav_msgs::Odometry::ConstPtr &msg)
UniversalTimeScaleClock::time_point Time
::cartographer::mapping::TrajectoryBuilderInterface *const trajectory_builder_
Definition: sensor_bridge.h:92
void HandleLaserScan(const std::string &sensor_id, ::cartographer::common::Time start_time, const std::string &frame_id, const ::cartographer::sensor::PointCloudWithIntensities &points)
::cartographer::common::optional<::cartographer::transform::Rigid3d > ecef_to_local_frame_
Definition: sensor_bridge.h:95
const TfBridge & tf_bridge() const
void HandlePointCloud2Message(const std::string &sensor_id, const sensor_msgs::PointCloud2::ConstPtr &msg)
void HandleOdometryMessage(const std::string &sensor_id, const nav_msgs::Odometry::ConstPtr &msg)
void HandleNavSatFixMessage(const std::string &sensor_id, const sensor_msgs::NavSatFix::ConstPtr &msg)
void HandleLandmarkMessage(const std::string &sensor_id, const cartographer_ros_msgs::LandmarkList::ConstPtr &msg)
std::map< std::string, cartographer::common::Time > sensor_to_previous_subdivision_time_
Definition: sensor_bridge.h:89
tf2_ros::Buffer * tf_buffer
void HandleLaserScanMessage(const std::string &sensor_id, const sensor_msgs::LaserScan::ConstPtr &msg)


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