Public Member Functions | |
PointCloudAggregator () | |
virtual | ~PointCloudAggregator () |
Private Types | |
typedef message_filters::sync_policies::ApproximateTime < sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2 > | MySyncPolicy |
Private Member Functions | |
void | clouds_callback (const sensor_msgs::PointCloud2ConstPtr &cloudMsg_1, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_2, const sensor_msgs::PointCloud2ConstPtr &cloudMsg_3) |
virtual void | onInit () |
Private Attributes | |
pcl::PointCloud< pcl::PointXYZ > | cloud1 |
pcl::PointCloud< pcl::PointXYZ > | cloud2 |
pcl::PointCloud< pcl::PointXYZ > | cloud3 |
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::Synchronizer < MySyncPolicy > * | sync |
Definition at line 26 of file point_cloud_aggregator.cpp.
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::MySyncPolicy [private] |
Definition at line 58 of file point_cloud_aggregator.cpp.
Definition at line 29 of file point_cloud_aggregator.cpp.
virtual rtabmap_ros::PointCloudAggregator::~PointCloudAggregator | ( | ) | [inline, virtual] |
Definition at line 32 of file point_cloud_aggregator.cpp.
void rtabmap_ros::PointCloudAggregator::clouds_callback | ( | const sensor_msgs::PointCloud2ConstPtr & | cloudMsg_1, |
const sensor_msgs::PointCloud2ConstPtr & | cloudMsg_2, | ||
const sensor_msgs::PointCloud2ConstPtr & | cloudMsg_3 | ||
) | [inline, private] |
Definition at line 38 of file point_cloud_aggregator.cpp.
virtual void rtabmap_ros::PointCloudAggregator::onInit | ( | ) | [inline, private, virtual] |
Implements nodelet::Nodelet.
Definition at line 59 of file point_cloud_aggregator.cpp.
pcl::PointCloud<pcl::PointXYZ> rtabmap_ros::PointCloudAggregator::cloud1 [private] |
Definition at line 81 of file point_cloud_aggregator.cpp.
pcl::PointCloud<pcl::PointXYZ> rtabmap_ros::PointCloudAggregator::cloud2 [private] |
Definition at line 81 of file point_cloud_aggregator.cpp.
pcl::PointCloud<pcl::PointXYZ> rtabmap_ros::PointCloudAggregator::cloud3 [private] |
Definition at line 81 of file point_cloud_aggregator.cpp.
Definition at line 83 of file point_cloud_aggregator.cpp.
message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::cloudSub_1_ [private] |
Definition at line 78 of file point_cloud_aggregator.cpp.
message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::cloudSub_2_ [private] |
Definition at line 79 of file point_cloud_aggregator.cpp.
message_filters::Subscriber<sensor_msgs::PointCloud2> rtabmap_ros::PointCloudAggregator::cloudSub_3_ [private] |
Definition at line 80 of file point_cloud_aggregator.cpp.
Definition at line 77 of file point_cloud_aggregator.cpp.