#include <sensor_bridge.h>
|
void | HandleImuMessage (const std::string &sensor_id, const sensor_msgs::Imu::ConstPtr &msg) |
|
void | HandleLandmarkMessage (const std::string &sensor_id, const cartographer_ros_msgs::LandmarkList::ConstPtr &msg) |
|
void | HandleLaserScanMessage (const std::string &sensor_id, const sensor_msgs::LaserScan::ConstPtr &msg) |
|
void | HandleMultiEchoLaserScanMessage (const std::string &sensor_id, const sensor_msgs::MultiEchoLaserScan::ConstPtr &msg) |
|
void | HandleNavSatFixMessage (const std::string &sensor_id, const sensor_msgs::NavSatFix::ConstPtr &msg) |
|
void | HandleOdometryMessage (const std::string &sensor_id, const nav_msgs::Odometry::ConstPtr &msg) |
|
void | HandlePointCloud2Message (const std::string &sensor_id, const sensor_msgs::PointCloud2::ConstPtr &msg) |
|
SensorBridge & | operator= (const SensorBridge &)=delete |
|
| 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) |
|
| SensorBridge (const SensorBridge &)=delete |
|
const TfBridge & | tf_bridge () const |
|
std::unique_ptr<::cartographer::sensor::ImuData > | ToImuData (const sensor_msgs::Imu::ConstPtr &msg) |
|
std::unique_ptr<::cartographer::sensor::OdometryData > | ToOdometryData (const nav_msgs::Odometry::ConstPtr &msg) |
|
Definition at line 43 of file sensor_bridge.h.
◆ SensorBridge() [1/2]
◆ SensorBridge() [2/2]
cartographer_ros::SensorBridge::SensorBridge |
( |
const SensorBridge & |
| ) |
|
|
delete |
◆ HandleImuMessage()
void cartographer_ros::SensorBridge::HandleImuMessage |
( |
const std::string & |
sensor_id, |
|
|
const sensor_msgs::Imu::ConstPtr & |
msg |
|
) |
| |
◆ HandleLandmarkMessage()
void cartographer_ros::SensorBridge::HandleLandmarkMessage |
( |
const std::string & |
sensor_id, |
|
|
const cartographer_ros_msgs::LandmarkList::ConstPtr & |
msg |
|
) |
| |
◆ HandleLaserScan()
◆ HandleLaserScanMessage()
void cartographer_ros::SensorBridge::HandleLaserScanMessage |
( |
const std::string & |
sensor_id, |
|
|
const sensor_msgs::LaserScan::ConstPtr & |
msg |
|
) |
| |
◆ HandleMultiEchoLaserScanMessage()
void cartographer_ros::SensorBridge::HandleMultiEchoLaserScanMessage |
( |
const std::string & |
sensor_id, |
|
|
const sensor_msgs::MultiEchoLaserScan::ConstPtr & |
msg |
|
) |
| |
◆ HandleNavSatFixMessage()
void cartographer_ros::SensorBridge::HandleNavSatFixMessage |
( |
const std::string & |
sensor_id, |
|
|
const sensor_msgs::NavSatFix::ConstPtr & |
msg |
|
) |
| |
◆ HandleOdometryMessage()
void cartographer_ros::SensorBridge::HandleOdometryMessage |
( |
const std::string & |
sensor_id, |
|
|
const nav_msgs::Odometry::ConstPtr & |
msg |
|
) |
| |
◆ HandlePointCloud2Message()
void cartographer_ros::SensorBridge::HandlePointCloud2Message |
( |
const std::string & |
sensor_id, |
|
|
const sensor_msgs::PointCloud2::ConstPtr & |
msg |
|
) |
| |
◆ HandleRangefinder()
◆ operator=()
◆ tf_bridge()
const TfBridge & cartographer_ros::SensorBridge::tf_bridge |
( |
| ) |
const |
◆ ToImuData()
std::unique_ptr< carto::sensor::ImuData > cartographer_ros::SensorBridge::ToImuData |
( |
const sensor_msgs::Imu::ConstPtr & |
msg | ) |
|
◆ ToOdometryData()
std::unique_ptr< carto::sensor::OdometryData > cartographer_ros::SensorBridge::ToOdometryData |
( |
const nav_msgs::Odometry::ConstPtr & |
msg | ) |
|
◆ ecef_to_local_frame_
◆ num_subdivisions_per_laser_scan_
const int cartographer_ros::SensorBridge::num_subdivisions_per_laser_scan_ |
|
private |
◆ sensor_to_previous_subdivision_time_
◆ tf_bridge_
const TfBridge cartographer_ros::SensorBridge::tf_bridge_ |
|
private |
◆ trajectory_builder_
The documentation for this class was generated from the following files: