|
| typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | ApproxSync2Policy |
| |
| typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | ApproxSync3Policy |
| |
| typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | ApproxSync4Policy |
| |
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | ExactSync2Policy |
| |
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | ExactSync3Policy |
| |
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | ExactSync4Policy |
| |
|
| void | clouds2_callback (const sensor_msgs::PointCloud2ConstPtr &cloudMsg_1, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_2) |
| |
| void | clouds3_callback (const sensor_msgs::PointCloud2ConstPtr &cloudMsg_1, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_2, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_3) |
| |
| void | clouds4_callback (const sensor_msgs::PointCloud2ConstPtr &cloudMsg_1, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_2, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_3, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_4) |
| |
| void | combineClouds (const std::vector< sensor_msgs::PointCloud2ConstPtr > &cloudMsgs) |
| |
| virtual void | onInit () |
| |
| void | warningLoop (const std::string &subscribedTopicsMsg, bool approxSync) |
| |
Definition at line 29 of file point_cloud_aggregator.cpp.
| rtabmap_ros::PointCloudAggregator::PointCloudAggregator |
( |
| ) |
|
|
inline |
| virtual rtabmap_ros::PointCloudAggregator::~PointCloudAggregator |
( |
| ) |
|
|
inlinevirtual |
| void rtabmap_ros::PointCloudAggregator::clouds2_callback |
( |
const sensor_msgs::PointCloud2ConstPtr & |
cloudMsg_1, |
|
|
const sensor_msgs::PointCloud2ConstPtr & |
cloudMsg_2 |
|
) |
| |
|
inlineprivate |
| void rtabmap_ros::PointCloudAggregator::clouds3_callback |
( |
const sensor_msgs::PointCloud2ConstPtr & |
cloudMsg_1, |
|
|
const sensor_msgs::PointCloud2ConstPtr & |
cloudMsg_2, |
|
|
const sensor_msgs::PointCloud2ConstPtr & |
cloudMsg_3 |
|
) |
| |
|
inlineprivate |
| void rtabmap_ros::PointCloudAggregator::clouds4_callback |
( |
const sensor_msgs::PointCloud2ConstPtr & |
cloudMsg_1, |
|
|
const sensor_msgs::PointCloud2ConstPtr & |
cloudMsg_2, |
|
|
const sensor_msgs::PointCloud2ConstPtr & |
cloudMsg_3, |
|
|
const sensor_msgs::PointCloud2ConstPtr & |
cloudMsg_4 |
|
) |
| |
|
inlineprivate |
| void rtabmap_ros::PointCloudAggregator::combineClouds |
( |
const std::vector< sensor_msgs::PointCloud2ConstPtr > & |
cloudMsgs | ) |
|
|
inlineprivate |
| virtual void rtabmap_ros::PointCloudAggregator::onInit |
( |
| ) |
|
|
inlineprivatevirtual |
| void rtabmap_ros::PointCloudAggregator::warningLoop |
( |
const std::string & |
subscribedTopicsMsg, |
|
|
bool |
approxSync |
|
) |
| |
|
inlineprivate |
| bool rtabmap_ros::PointCloudAggregator::callbackCalled_ |
|
private |
| std::string rtabmap_ros::PointCloudAggregator::frameId_ |
|
private |
| boost::thread* rtabmap_ros::PointCloudAggregator::warningThread_ |
|
private |
The documentation for this class was generated from the following file: