cluster_point_indices_decomposer.h
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2013, Ryohei Ueda and JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #ifndef JSK_PCL_ROS_CLUSTER_POINT_INDICES_DECOMPOSER_H_
37 #define JSK_PCL_ROS_CLUSTER_POINT_INDICES_DECOMPOSER_H_
38 
39 #include <ros/ros.h>
40 #include <ros/names.h>
41 
42 #include "jsk_recognition_msgs/ClusterPointIndices.h"
43 #include "jsk_recognition_msgs/PolygonArray.h"
44 #include "jsk_recognition_msgs/ModelCoefficientsArray.h"
46 
47 #include "sensor_msgs/PointCloud2.h"
48 #include <dynamic_reconfigure/server.h>
49 #include <pcl_ros/pcl_nodelet.h>
53 #include <pcl/point_types.h>
54 #include <pcl/impl/point_types.hpp>
56 #include <std_msgs/ColorRGBA.h>
57 #include <jsk_recognition_msgs/BoundingBoxArray.h>
58 
64 #include "jsk_pcl_ros/ClusterPointIndicesDecomposerConfig.h"
65 
66 namespace jsk_pcl_ros
67 {
69  {
70  public:
71  ClusterPointIndicesDecomposer(): DiagnosticNodelet("ClusterPointIndicesDecomposer") { }
72  typedef jsk_pcl_ros::ClusterPointIndicesDecomposerConfig Config;
74  sensor_msgs::PointCloud2,
75  jsk_recognition_msgs::ClusterPointIndices > SyncPolicy;
77  sensor_msgs::PointCloud2,
78  jsk_recognition_msgs::ClusterPointIndices > ApproximateSyncPolicy;
80  sensor_msgs::PointCloud2,
81  jsk_recognition_msgs::ClusterPointIndices,
82  jsk_recognition_msgs::PolygonArray,
83  jsk_recognition_msgs::ModelCoefficientsArray> SyncAlignPolicy;
85  sensor_msgs::PointCloud2,
86  jsk_recognition_msgs::ClusterPointIndices,
87  jsk_recognition_msgs::PolygonArray,
88  jsk_recognition_msgs::ModelCoefficientsArray> ApproximateSyncAlignPolicy;
89  virtual void onInit();
90  virtual void extract(const sensor_msgs::PointCloud2ConstPtr &point,
91  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices,
92  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
93  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients);
94  virtual void extract(const sensor_msgs::PointCloud2ConstPtr &point,
95  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices);
96  virtual void sortIndicesOrder(const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
97  const std::vector<pcl::IndicesPtr> indices_array,
98  std::vector<size_t>* argsort);
99  void sortIndicesOrderByIndices(const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
100  const std::vector<pcl::IndicesPtr> indices_array,
101  std::vector<size_t>* argsort);
102  void sortIndicesOrderByZAxis(const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
103  const std::vector<pcl::IndicesPtr> indices_array,
104  std::vector<size_t>* argsort);
105  void sortIndicesOrderByCloudSize(const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
106  const std::vector<pcl::IndicesPtr> indices_array,
107  std::vector<size_t>* argsort);
108  protected:
111 
113  (const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
114  size_t i,
115  pcl::PointCloud<pcl::PointXYZRGB>& debug_output);
116 
117  virtual bool computeCenterAndBoundingBox
118  (const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
119  const std_msgs::Header header,
120  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
121  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
122  geometry_msgs::Pose& center_pose_msg,
123  jsk_recognition_msgs::BoundingBox& bounding_box);
124 
126  const pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud,
127  pcl::PointCloud<pcl::PointXYZRGB>::Ptr segmented_cloud_transformed,
128  const Eigen::Vector4f center,
129  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
130  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
131  Eigen::Matrix4f& m4,
132  Eigen::Quaternionf& q,
133  int& nearest_plane_index);
134 
135  virtual int findNearestPlane(const Eigen::Vector4f& center,
136  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
137  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients);
138 
139  virtual void configCallback (Config &config, uint32_t level);
140  virtual void updateDiagnostic(
142  virtual void allocatePublishers(size_t num);
143  virtual void publishNegativeIndices(
144  const sensor_msgs::PointCloud2ConstPtr &input,
145  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input);
146  virtual void subscribe();
147  virtual void unsubscribe();
148 
149  static uint32_t colorRGBAToUInt32(std_msgs::ColorRGBA c)
150  {
151  uint8_t r, g, b;
152  r = (uint8_t)(c.r * 255);
153  g = (uint8_t)(c.g * 255);
154  b = (uint8_t)(c.b * 255);
155  return ((uint32_t)r<<16 | (uint32_t)g<<8 | (uint32_t)b);
156  }
157 
166  std::vector<ros::Publisher> publishers_;
169  std::string tf_prefix_;
170 
178  std::string target_frame_id_;
180  bool use_pca_;
184  std::string sort_by_;
185 
187 
188  };
189 
191  {
192  public:
193  virtual void onInit();
194  };
195 
196 } // namespace jsk_pcl_ros
197 
198 #endif // JSK_PCL_ROS_CLUSTER_POINT_INDICES_DECOMPOSER_H_
static uint32_t colorRGBAToUInt32(std_msgs::ColorRGBA c)
virtual bool computeCenterAndBoundingBox(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud, const std_msgs::Header header, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients, geometry_msgs::Pose &center_pose_msg, jsk_recognition_msgs::BoundingBox &bounding_box)
virtual void configCallback(Config &config, uint32_t level)
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > SyncAlignPolicy
void sortIndicesOrderByZAxis(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncAlignPolicy > > async_align_
virtual bool transformPointCloudToAlignWithPlane(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud, pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud_transformed, const Eigen::Vector4f center, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients, Eigen::Matrix4f &m4, Eigen::Quaternionf &q, int &nearest_plane_index)
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > ApproximateSyncAlignPolicy
DiagnosticNodelet(const std::string &name)
void sortIndicesOrderByCloudSize(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< tf::TransformBroadcaster > br_
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_target_
virtual void publishNegativeIndices(const sensor_msgs::PointCloud2ConstPtr &input, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
jsk_pcl_ros::ClusterPointIndicesDecomposerConfig Config
virtual int findNearestPlane(const Eigen::Vector4f &center, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients)
void sortIndicesOrderByIndices(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
boost::mutex mutex
global mutex.
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
void addToDebugPointCloud(const pcl::PointCloud< pcl::PointXYZRGB >::Ptr segmented_cloud, size_t i, pcl::PointCloud< pcl::PointXYZRGB > &debug_output)
virtual void sortIndicesOrder(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
virtual void extract(const sensor_msgs::PointCloud2ConstPtr &point, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients)
boost::shared_ptr< message_filters::Synchronizer< SyncAlignPolicy > > sync_align_
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > ApproximateSyncPolicy
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46