17 #ifndef CARTOGRAPHER_ROS_SENSOR_BRIDGE_H_ 18 #define CARTOGRAPHER_ROS_SENSOR_BRIDGE_H_ 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" 39 const string& tracking_frame,
double lookup_transform_timeout_sec,
41 ::cartographer::mapping::TrajectoryBuilder* trajectory_builder);
47 const nav_msgs::Odometry::ConstPtr& msg);
49 const sensor_msgs::Imu::ConstPtr& msg);
51 const sensor_msgs::LaserScan::ConstPtr& msg);
53 const string& sensor_id,
54 const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg);
56 const sensor_msgs::PointCloud2::ConstPtr& msg);
62 const ::cartographer::common::Time
time,
63 const string& frame_id,
64 const ::cartographer::sensor::PointCloud& ranges);
72 #endif // CARTOGRAPHER_ROS_SENSOR_BRIDGE_H_
::cartographer::mapping::TrajectoryBuilder *const trajectory_builder_
void HandlePointCloud2Message(const string &sensor_id, const sensor_msgs::PointCloud2::ConstPtr &msg)
SensorBridge & operator=(const SensorBridge &)=delete
const TfBridge & tf_bridge() const
const TfBridge tf_bridge_
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