36 #ifndef JSK_RECOGNITION_UTILS_PCL_UTIL_H_ 
   37 #define JSK_RECOGNITION_UTILS_PCL_UTIL_H_ 
   38 #include <pcl/point_types.h> 
   40 #include <boost/accumulators/accumulators.hpp> 
   41 #include <boost/accumulators/statistics/stats.hpp> 
   42 #include <boost/accumulators/statistics/min.hpp> 
   43 #include <boost/accumulators/statistics/max.hpp> 
   44 #include <boost/accumulators/statistics/variance.hpp> 
   45 #include <boost/accumulators/statistics/count.hpp> 
   50 #include <sensor_msgs/PointCloud2.h> 
   52 #include <pcl/PointIndices.h> 
   53 #include <std_msgs/ColorRGBA.h> 
   55 #include <jsk_topic_tools/time_accumulator.h> 
   56 #include <jsk_topic_tools/timered_diagnostic_updater.h> 
   58 #include <boost/circular_buffer.hpp> 
   59 #include <jsk_topic_tools/vital_checker.h> 
   61 #include <pcl/filters/extract_indices.h> 
   62 #include <yaml-cpp/yaml.h> 
   68   std::vector<int> 
addIndices(
const std::vector<int>& a,
 
   69                               const std::vector<int>& b);
 
   70   pcl::PointIndices::Ptr 
addIndices(
const pcl::PointIndices& a,
 
   71                                     const pcl::PointIndices& b);
 
   73   std::vector<int> 
subIndices(
const std::vector<int>& a,
 
   74                               const std::vector<int>& b);
 
   75   pcl::PointIndices::Ptr 
subIndices(
const pcl::PointIndices& a,
 
   76                                     const pcl::PointIndices& b);
 
   78   template <
class Po
intT>
 
   79   std::vector<typename pcl::PointCloud<PointT> ::Ptr>
 
   81                            const std::vector<pcl::PointIndices::Ptr>& indices)
 
   83     pcl::ExtractIndices<PointT> extract;
 
   84     extract.setInputCloud(cloud);
 
   85     std::vector<typename pcl::PointCloud<PointT> ::Ptr> cloud_array;
 
   86     for (
size_t i = 0; 
i < indices.size(); 
i++) {
 
   87       typename pcl::PointCloud<PointT> ::Ptr
 
   88         segment (
new pcl::PointCloud<PointT>);
 
   89       extract.setIndices(indices[i]);
 
   90       extract.filter(*segment);
 
   91       cloud_array.push_back(segment);
 
   98   pcl::PointCloud<pcl::PointXYZ>::Ptr 
convertToXYZCloud(
const pcl::PointCloud<T>& cloud)
 
  100     pcl::PointCloud<pcl::PointXYZ>::Ptr output(
new pcl::PointCloud<pcl::PointXYZ>);
 
  101     output->points.resize(cloud.points.size());
 
  102     for (
size_t i = 0; 
i < cloud.points.size(); 
i++) {
 
  104       p.x = cloud.points[
i].x;
 
  105       p.y = cloud.points[
i].y;
 
  106       p.z = cloud.points[
i].z;
 
  107       output->points[
i] = 
p;
 
  113   void appendVector(std::vector<T>& a, 
const std::vector<T>& b)
 
  115     for (
size_t i = 0; 
i < b.size(); 
i++) {
 
  126     typedef boost::accumulators::accumulator_set<
 
  128     boost::accumulators::stats<boost::accumulators::tag::count,
 
  129                                boost::accumulators::tag::mean,
 
  130                                boost::accumulators::tag::min,
 
  131                                boost::accumulators::tag::max,
 
  133     virtual void add(
double v);
 
  134     virtual double mean();
 
  135     virtual double min();
 
  136     virtual double max();
 
  164                               const int from_index,
 
  165                               std::vector<int>& to_indices,
 
  166                               std::set<int>& output_set);
 
  168                               const int from_index,
 
  169                               std::vector<int>& to_indices,
 
  170                               std::set<int>& output_set);
 
  177                                      std::vector<std::set<int> >& output_sets);
 
  184   void addSet(std::set<T>& output,
 
  185               const std::set<T>& new_set)
 
  187     typedef typename std::set<T> Set;
 
  188     typedef typename Set::iterator Iterator;
 
  189     for (Iterator it = new_set.begin();
 
  201   class SeriesedBoolean
 
  210     virtual void clear();
 
  213     boost::circular_buffer<bool> 
buf_;