00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00039 #ifndef LASER_SLAM_COLLECT_CLOUDS_H
00040 #define LASER_SLAM_COLLECT_CLOUDS_H
00041
00042 #include <laser_slam/CloudCollectorConfig.h>
00043 #include <pcl_ros/filters/filter.h>
00044 #include <tf/transform_listener.h>
00045
00046 namespace laser_slam
00047 {
00048
00050 class CloudCollector: public pcl::Filter<sensor_msgs::PointCloud2>
00051 {
00052 using pcl::Filter<sensor_msgs::PointCloud2>::filter_name_;
00053
00054 public:
00055
00057 CloudCollector (unsigned clouds_per_group = 1u) :
00058 clouds_per_group_(clouds_per_group)
00059 {
00060 filter_name_ = "CloudCollector";
00061 }
00062
00063 private:
00064
00065 friend class CloudCollectorROS;
00066
00068 int clouds_per_group_;
00069
00071 std::string fixed_frame_;
00072
00074 std::string base_frame_;
00075
00077 std::vector<sensor_msgs::PointCloud2> stored_clouds_;
00078
00079 pcl::PointCloud<pcl::PointXYZ> cloud_;
00080 unsigned num_clouds_;
00081
00082 tf::TransformListener tf_;
00083
00086 virtual void applyFilter (sensor_msgs::PointCloud2& output);
00087
00088 };
00089
00090
00092 class CloudCollectorROS : public pcl_ros::Filter
00093 {
00094 protected:
00095
00096 virtual void onInit ();
00097
00098 inline void
00099 filter (const PointCloud2::ConstPtr& input, const IndicesConstPtr& indices,
00100 PointCloud2& output)
00101 {
00102 impl_.setInputCloud(input);
00103 impl_.setIndices(indices);
00104 impl_.filter(output);
00105 }
00106
00107
00108
00109 virtual inline bool child_init (ros::NodeHandle& nh)
00110 {
00111 return true;
00112 }
00113
00114 private:
00115
00116 CloudCollector impl_;
00117
00118 };
00119
00120
00121 }
00122
00123 #endif // include guard