
| Public Member Functions | |
| PointCloudAggregator () | |
| virtual | ~PointCloudAggregator () | 
| Private Types | |
| 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 | 
| Private Member Functions | |
| 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) | 
| Private Attributes | |
| message_filters::Synchronizer < ApproxSync2Policy > * | approxSync2_ | 
| message_filters::Synchronizer < ApproxSync3Policy > * | approxSync3_ | 
| message_filters::Synchronizer < ApproxSync4Policy > * | approxSync4_ | 
| bool | callbackCalled_ | 
| ros::Publisher | cloudPub_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | cloudSub_1_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | cloudSub_2_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | cloudSub_3_ | 
| message_filters::Subscriber < sensor_msgs::PointCloud2 > | cloudSub_4_ | 
| message_filters::Synchronizer < ExactSync2Policy > * | exactSync2_ | 
| message_filters::Synchronizer < ExactSync3Policy > * | exactSync3_ | 
| message_filters::Synchronizer < ExactSync4Policy > * | exactSync4_ | 
| std::string | frameId_ | 
| tf::TransformListener | tfListener_ | 
| boost::thread * | warningThread_ | 
Definition at line 29 of file point_cloud_aggregator.cpp.
| typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::ApproxSync2Policy  [private] | 
Definition at line 254 of file point_cloud_aggregator.cpp.
| typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::ApproxSync3Policy  [private] | 
Definition at line 252 of file point_cloud_aggregator.cpp.
| typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::ApproxSync4Policy  [private] | 
Definition at line 250 of file point_cloud_aggregator.cpp.
| typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::ExactSync2Policy  [private] | 
Definition at line 253 of file point_cloud_aggregator.cpp.
| typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::ExactSync3Policy  [private] | 
Definition at line 251 of file point_cloud_aggregator.cpp.
| typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::ExactSync4Policy  [private] | 
Definition at line 249 of file point_cloud_aggregator.cpp.
Definition at line 32 of file point_cloud_aggregator.cpp.
| virtual rtabmap_ros::PointCloudAggregator::~PointCloudAggregator | ( | ) |  [inline, virtual] | 
Definition at line 43 of file point_cloud_aggregator.cpp.
| void rtabmap_ros::PointCloudAggregator::clouds2_callback | ( | const sensor_msgs::PointCloud2ConstPtr & | cloudMsg_1, | 
| const sensor_msgs::PointCloud2ConstPtr & | cloudMsg_2 | ||
| ) |  [inline, private] | 
Definition at line 169 of file point_cloud_aggregator.cpp.
| void rtabmap_ros::PointCloudAggregator::clouds3_callback | ( | const sensor_msgs::PointCloud2ConstPtr & | cloudMsg_1, | 
| const sensor_msgs::PointCloud2ConstPtr & | cloudMsg_2, | ||
| const sensor_msgs::PointCloud2ConstPtr & | cloudMsg_3 | ||
| ) |  [inline, private] | 
Definition at line 158 of file point_cloud_aggregator.cpp.
| 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 | ||
| ) |  [inline, private] | 
Definition at line 145 of file point_cloud_aggregator.cpp.
| void rtabmap_ros::PointCloudAggregator::combineClouds | ( | const std::vector< sensor_msgs::PointCloud2ConstPtr > & | cloudMsgs | ) |  [inline, private] | 
Definition at line 178 of file point_cloud_aggregator.cpp.
| virtual void rtabmap_ros::PointCloudAggregator::onInit | ( | ) |  [inline, private, virtual] | 
Implements nodelet::Nodelet.
Definition at line 61 of file point_cloud_aggregator.cpp.
| void rtabmap_ros::PointCloudAggregator::warningLoop | ( | const std::string & | subscribedTopicsMsg, | 
| bool | approxSync | ||
| ) |  [inline, private] | 
Definition at line 227 of file point_cloud_aggregator.cpp.
| message_filters::Synchronizer<ApproxSync2Policy>* rtabmap_ros::PointCloudAggregator::approxSync2_  [private] | 
Definition at line 260 of file point_cloud_aggregator.cpp.
| message_filters::Synchronizer<ApproxSync3Policy>* rtabmap_ros::PointCloudAggregator::approxSync3_  [private] | 
Definition at line 258 of file point_cloud_aggregator.cpp.
| message_filters::Synchronizer<ApproxSync4Policy>* rtabmap_ros::PointCloudAggregator::approxSync4_  [private] | 
Definition at line 256 of file point_cloud_aggregator.cpp.
| bool rtabmap_ros::PointCloudAggregator::callbackCalled_  [private] | 
Definition at line 247 of file point_cloud_aggregator.cpp.
Definition at line 266 of file point_cloud_aggregator.cpp.
| message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::cloudSub_1_  [private] | 
Definition at line 261 of file point_cloud_aggregator.cpp.
| message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::cloudSub_2_  [private] | 
Definition at line 262 of file point_cloud_aggregator.cpp.
| message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::cloudSub_3_  [private] | 
Definition at line 263 of file point_cloud_aggregator.cpp.
| message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::cloudSub_4_  [private] | 
Definition at line 264 of file point_cloud_aggregator.cpp.
| message_filters::Synchronizer<ExactSync2Policy>* rtabmap_ros::PointCloudAggregator::exactSync2_  [private] | 
Definition at line 259 of file point_cloud_aggregator.cpp.
| message_filters::Synchronizer<ExactSync3Policy>* rtabmap_ros::PointCloudAggregator::exactSync3_  [private] | 
Definition at line 257 of file point_cloud_aggregator.cpp.
| message_filters::Synchronizer<ExactSync4Policy>* rtabmap_ros::PointCloudAggregator::exactSync4_  [private] | 
Definition at line 255 of file point_cloud_aggregator.cpp.
| std::string rtabmap_ros::PointCloudAggregator::frameId_  [private] | 
Definition at line 268 of file point_cloud_aggregator.cpp.
Definition at line 269 of file point_cloud_aggregator.cpp.
| boost::thread* rtabmap_ros::PointCloudAggregator::warningThread_  [private] | 
Definition at line 246 of file point_cloud_aggregator.cpp.