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_SENSOR_BRIDGE_H_
18 #define CARTOGRAPHER_ROS_SENSOR_BRIDGE_H_
19 
20 #include "cartographer/mapping/trajectory_builder.h"
24 #include "geometry_msgs/Transform.h"
25 #include "geometry_msgs/TransformStamped.h"
26 #include "nav_msgs/OccupancyGrid.h"
27 #include "nav_msgs/Odometry.h"
28 #include "sensor_msgs/Imu.h"
29 #include "sensor_msgs/LaserScan.h"
30 #include "sensor_msgs/MultiEchoLaserScan.h"
31 #include "sensor_msgs/PointCloud2.h"
32 
33 namespace cartographer_ros {
34 
35 // Converts ROS messages into SensorData in tracking frame for the MapBuilder.
36 class SensorBridge {
37  public:
38  explicit SensorBridge(
39  const string& tracking_frame, double lookup_transform_timeout_sec,
41  ::cartographer::mapping::TrajectoryBuilder* trajectory_builder);
42 
43  SensorBridge(const SensorBridge&) = delete;
44  SensorBridge& operator=(const SensorBridge&) = delete;
45 
46  void HandleOdometryMessage(const string& sensor_id,
47  const nav_msgs::Odometry::ConstPtr& msg);
48  void HandleImuMessage(const string& sensor_id,
49  const sensor_msgs::Imu::ConstPtr& msg);
50  void HandleLaserScanMessage(const string& sensor_id,
51  const sensor_msgs::LaserScan::ConstPtr& msg);
53  const string& sensor_id,
54  const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg);
55  void HandlePointCloud2Message(const string& sensor_id,
56  const sensor_msgs::PointCloud2::ConstPtr& msg);
57 
58  const TfBridge& tf_bridge() const;
59 
60  private:
61  void HandleRangefinder(const string& sensor_id,
62  const ::cartographer::common::Time time,
63  const string& frame_id,
64  const ::cartographer::sensor::PointCloud& ranges);
65 
67  ::cartographer::mapping::TrajectoryBuilder* const trajectory_builder_;
68 };
69 
70 } // namespace cartographer_ros
71 
72 #endif // CARTOGRAPHER_ROS_SENSOR_BRIDGE_H_
::cartographer::mapping::TrajectoryBuilder *const trajectory_builder_
Definition: sensor_bridge.h:67
void HandlePointCloud2Message(const string &sensor_id, const sensor_msgs::PointCloud2::ConstPtr &msg)
SensorBridge & operator=(const SensorBridge &)=delete
const TfBridge & tf_bridge() const
const common::Time time
void HandleRangefinder(const string &sensor_id, const ::cartographer::common::Time time, const string &frame_id, const ::cartographer::sensor::PointCloud &ranges)
void HandleMultiEchoLaserScanMessage(const string &sensor_id, const sensor_msgs::MultiEchoLaserScan::ConstPtr &msg)
SensorBridge(const string &tracking_frame, double lookup_transform_timeout_sec, tf2_ros::Buffer *tf_buffer,::cartographer::mapping::TrajectoryBuilder *trajectory_builder)
void HandleLaserScanMessage(const string &sensor_id, const sensor_msgs::LaserScan::ConstPtr &msg)
void HandleImuMessage(const string &sensor_id, const sensor_msgs::Imu::ConstPtr &msg)
void HandleOdometryMessage(const string &sensor_id, const nav_msgs::Odometry::ConstPtr &msg)
tf2_ros::Buffer * tf_buffer


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