#include <sensor_bridge.h>
Definition at line 36 of file sensor_bridge.h.
cartographer_ros::SensorBridge::SensorBridge |
( |
const string & |
tracking_frame, |
|
|
double |
lookup_transform_timeout_sec, |
|
|
tf2_ros::Buffer * |
tf_buffer, |
|
|
::cartographer::mapping::TrajectoryBuilder * |
trajectory_builder |
|
) |
| |
|
explicit |
cartographer_ros::SensorBridge::SensorBridge |
( |
const SensorBridge & |
| ) |
|
|
delete |
void cartographer_ros::SensorBridge::HandleImuMessage |
( |
const string & |
sensor_id, |
|
|
const sensor_msgs::Imu::ConstPtr & |
msg |
|
) |
| |
void cartographer_ros::SensorBridge::HandleLaserScanMessage |
( |
const string & |
sensor_id, |
|
|
const sensor_msgs::LaserScan::ConstPtr & |
msg |
|
) |
| |
void cartographer_ros::SensorBridge::HandleMultiEchoLaserScanMessage |
( |
const string & |
sensor_id, |
|
|
const sensor_msgs::MultiEchoLaserScan::ConstPtr & |
msg |
|
) |
| |
void cartographer_ros::SensorBridge::HandleOdometryMessage |
( |
const string & |
sensor_id, |
|
|
const nav_msgs::Odometry::ConstPtr & |
msg |
|
) |
| |
void cartographer_ros::SensorBridge::HandlePointCloud2Message |
( |
const string & |
sensor_id, |
|
|
const sensor_msgs::PointCloud2::ConstPtr & |
msg |
|
) |
| |
const TfBridge & cartographer_ros::SensorBridge::tf_bridge |
( |
| ) |
const |
const TfBridge cartographer_ros::SensorBridge::tf_bridge_ |
|
private |
::cartographer::mapping::TrajectoryBuilder* const cartographer_ros::SensorBridge::trajectory_builder_ |
|
private |
The documentation for this class was generated from the following files: