17 #ifndef CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_SENSOR_BRIDGE_H 18 #define CARTOGRAPHER_ROS_CARTOGRAPHER_ROS_SENSOR_BRIDGE_H 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" 46 int num_subdivisions_per_laser_scan,
const std::string& tracking_frame,
53 std::unique_ptr<::cartographer::sensor::OdometryData>
ToOdometryData(
54 const nav_msgs::Odometry::ConstPtr& msg);
56 const nav_msgs::Odometry::ConstPtr& msg);
58 const sensor_msgs::NavSatFix::ConstPtr& msg);
60 const std::string& sensor_id,
61 const cartographer_ros_msgs::LandmarkList::ConstPtr& msg);
63 std::unique_ptr<::cartographer::sensor::ImuData>
ToImuData(
64 const sensor_msgs::Imu::ConstPtr& msg);
66 const sensor_msgs::Imu::ConstPtr& msg);
68 const sensor_msgs::LaserScan::ConstPtr& msg);
70 const std::string& sensor_id,
71 const sensor_msgs::MultiEchoLaserScan::ConstPtr& msg);
73 const sensor_msgs::PointCloud2::ConstPtr& msg);
80 const std::string& frame_id,
81 const ::cartographer::sensor::PointCloudWithIntensities& points);
84 const std::string& frame_id,
85 const ::cartographer::sensor::TimedPointCloud& ranges);
88 std::map<std::string, cartographer::common::Time>
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)
const int num_subdivisions_per_laser_scan_
SensorBridge & operator=(const SensorBridge &)=delete
void HandleImuMessage(const std::string &sensor_id, const sensor_msgs::Imu::ConstPtr &msg)
const TfBridge tf_bridge_
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)
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_
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_
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_
tf2_ros::Buffer * tf_buffer
void HandleLaserScanMessage(const std::string &sensor_id, const sensor_msgs::LaserScan::ConstPtr &msg)