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/or 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 
62 #include <jsk_topic_tools/vital_checker.h>
63 #include "jsk_topic_tools/diagnostic_nodelet.h"
64 #include "jsk_pcl_ros/ClusterPointIndicesDecomposerConfig.h"
65 
66 namespace jsk_pcl_ros
67 {
68  class ClusterPointIndicesDecomposer: public jsk_topic_tools::DiagnosticNodelet
69  {
70  public:
71  ClusterPointIndicesDecomposer(): DiagnosticNodelet("ClusterPointIndicesDecomposer") { }
73  typedef jsk_pcl_ros::ClusterPointIndicesDecomposerConfig Config;
75  sensor_msgs::PointCloud2,
76  jsk_recognition_msgs::ClusterPointIndices > SyncPolicy;
78  sensor_msgs::PointCloud2,
79  jsk_recognition_msgs::ClusterPointIndices > ApproximateSyncPolicy;
81  sensor_msgs::PointCloud2,
82  jsk_recognition_msgs::ClusterPointIndices,
83  jsk_recognition_msgs::PolygonArray,
84  jsk_recognition_msgs::ModelCoefficientsArray> SyncAlignPolicy;
86  sensor_msgs::PointCloud2,
87  jsk_recognition_msgs::ClusterPointIndices,
88  jsk_recognition_msgs::PolygonArray,
89  jsk_recognition_msgs::ModelCoefficientsArray> ApproximateSyncAlignPolicy;
90  virtual void onInit();
91  virtual void extract(const sensor_msgs::PointCloud2ConstPtr &point,
92  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices,
93  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
94  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients);
95  virtual void extract(const sensor_msgs::PointCloud2ConstPtr &point,
96  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices);
97  virtual void sortIndicesOrder(const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
98  const std::vector<pcl::IndicesPtr> indices_array,
99  std::vector<size_t>* argsort);
100  void sortIndicesOrderByIndices(const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
101  const std::vector<pcl::IndicesPtr> indices_array,
102  std::vector<size_t>* argsort);
103  void sortIndicesOrderByZAxis(const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
104  const std::vector<pcl::IndicesPtr> indices_array,
105  std::vector<size_t>* argsort);
106  void sortIndicesOrderByCloudSize(const pcl::PointCloud<pcl::PointXYZ>::Ptr input,
107  const std::vector<pcl::IndicesPtr> indices_array,
108  std::vector<size_t>* argsort);
109  protected:
112 
114  (const pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud,
115  size_t i,
116  pcl::PointCloud<pcl::PointXYZRGB>& debug_output);
117 
118  virtual bool computeCenterAndBoundingBox
119  (const pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud,
120  const std_msgs::Header header,
121  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
122  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
123  geometry_msgs::Pose& center_pose_msg,
124  jsk_recognition_msgs::BoundingBox& bounding_box,
125  bool& publish_tf);
126 
128  const pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud,
129  pcl::PointCloud<pcl::PointXYZ>::Ptr segmented_cloud_transformed,
130  const Eigen::Vector4f center,
131  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
132  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients,
133  Eigen::Matrix4f& m4,
134  Eigen::Quaternionf& q,
135  int& nearest_plane_index);
136 
137  virtual int findNearestPlane(const Eigen::Vector4f& center,
138  const jsk_recognition_msgs::PolygonArrayConstPtr& planes,
139  const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr& coefficients);
140 
141  virtual void configCallback (Config &config, uint32_t level);
142  virtual void updateDiagnostic(
144  virtual void allocatePublishers(size_t num);
145  virtual void publishNegativeIndices(
146  const sensor_msgs::PointCloud2ConstPtr &input,
147  const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input);
148  virtual void subscribe();
149  virtual void unsubscribe();
150 
151  static uint32_t colorRGBAToUInt32(std_msgs::ColorRGBA c)
152  {
153  uint8_t r, g, b;
154  r = (uint8_t)(c.r * 255);
155  g = (uint8_t)(c.g * 255);
156  b = (uint8_t)(c.b * 255);
157  return ((uint32_t)r<<16 | (uint32_t)g<<8 | (uint32_t)b);
158  }
159 
168  std::vector<ros::Publisher> publishers_;
171  std::string tf_prefix_;
172 
173  bool use_async_;
176  bool publish_clouds_;
177  bool publish_tf_;
178  bool align_boxes_;
180  std::string target_frame_id_;
182  bool use_pca_;
184  int max_size_;
185  int min_size_;
186  std::string sort_by_;
187 
189 
190  };
191 
193  {
194  public:
195  virtual void onInit();
196  };
197 
198 } // namespace jsk_pcl_ros
199 
200 #endif // JSK_PCL_ROS_CLUSTER_POINT_INDICES_DECOMPOSER_H_
jsk_pcl_ros::ClusterPointIndicesDecomposer::addToDebugPointCloud
void addToDebugPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr segmented_cloud, size_t i, pcl::PointCloud< pcl::PointXYZRGB > &debug_output)
Definition: cluster_point_indices_decomposer_nodelet.cpp:659
jsk_pcl_ros::ClusterPointIndicesDecomposer::use_async_
bool use_async_
Definition: cluster_point_indices_decomposer.h:237
jsk_pcl_ros::ClusterPointIndicesDecomposer::label_pub_
ros::Publisher label_pub_
Definition: cluster_point_indices_decomposer.h:233
ros::Publisher
boost::shared_ptr
jsk_pcl_ros::ClusterPointIndicesDecomposer::SyncAlignPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > SyncAlignPolicy
Definition: cluster_point_indices_decomposer.h:148
jsk_pcl_ros::ClusterPointIndicesDecomposer::subscribe
virtual void subscribe()
Definition: cluster_point_indices_decomposer_nodelet.cpp:178
jsk_pcl_ros::ClusterPointIndicesDecomposer::sub_coefficients_
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
Definition: cluster_point_indices_decomposer.h:227
sample_simulate_tabletop_cloud.header
header
Definition: sample_simulate_tabletop_cloud.py:162
jsk_pcl_ros::ClusterPointIndicesDecomposer::publish_clouds_
bool publish_clouds_
Definition: cluster_point_indices_decomposer.h:240
jsk_pcl_ros::ClusterPointIndicesDecomposer::indices_pub_
ros::Publisher indices_pub_
Definition: cluster_point_indices_decomposer.h:233
ros.h
jsk_pcl_ros::ClusterPointIndicesDecomposer::min_size_
int min_size_
Definition: cluster_point_indices_decomposer.h:249
jsk_pcl_ros::ClusterPointIndicesDecomposer::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: cluster_point_indices_decomposer.h:229
jsk_pcl_ros::ClusterPointIndicesDecomposer::target_frame_id_
std::string target_frame_id_
Definition: cluster_point_indices_decomposer.h:244
jsk_pcl_ros::ClusterPointIndicesDecomposerZAxis
Definition: cluster_point_indices_decomposer.h:224
jsk_pcl_ros::ClusterPointIndicesDecomposer::mutex_
boost::mutex mutex_
Definition: cluster_point_indices_decomposer.h:175
jsk_pcl_ros::ClusterPointIndicesDecomposer::ApproximateSyncAlignPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > ApproximateSyncAlignPolicy
Definition: cluster_point_indices_decomposer.h:153
time_synchronizer.h
simulate_primitive_shape_on_plane.c
c
Definition: simulate_primitive_shape_on_plane.py:103
jsk_pcl_ros::ClusterPointIndicesDecomposer::sub_target_
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_target_
Definition: cluster_point_indices_decomposer.h:225
jsk_pcl_ros::ClusterPointIndicesDecomposer::async_align_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncAlignPolicy > > async_align_
Definition: cluster_point_indices_decomposer.h:231
jsk_pcl_ros::ClusterPointIndicesDecomposer::align_boxes_
bool align_boxes_
Definition: cluster_point_indices_decomposer.h:242
publisher.h
jsk_pcl_ros::ClusterPointIndicesDecomposer::computeCenterAndBoundingBox
virtual bool computeCenterAndBoundingBox(const pcl::PointCloud< pcl::PointXYZ >::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, bool &publish_tf)
Definition: cluster_point_indices_decomposer_nodelet.cpp:473
transform_broadcaster.h
jsk_pcl_ros::ClusterPointIndicesDecomposer::tf_listener_
tf::TransformListener * tf_listener_
Definition: cluster_point_indices_decomposer.h:245
diagnostic_updater.h
message_filters::Subscriber< sensor_msgs::PointCloud2 >
jsk_pcl_ros::ClusterPointIndicesDecomposer::sortIndicesOrderByZAxis
void sortIndicesOrderByZAxis(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
Definition: cluster_point_indices_decomposer_nodelet.cpp:269
pcl_nodelet.h
jsk_pcl_ros::ClusterPointIndicesDecomposer::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: cluster_point_indices_decomposer_nodelet.cpp:169
message_filters::sync_policies::ApproximateTime
jsk_pcl_ros::ClusterPointIndicesDecomposer::tf_prefix_
std::string tf_prefix_
Definition: cluster_point_indices_decomposer.h:235
jsk_pcl_ros
Definition: add_color_from_image.h:51
jsk_pcl_ros::ClusterPointIndicesDecomposer::br_
boost::shared_ptr< tf::TransformBroadcaster > br_
Definition: cluster_point_indices_decomposer.h:234
subscriber.h
jsk_pcl_ros::ClusterPointIndicesDecomposer::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: cluster_point_indices_decomposer.h:174
jsk_pcl_ros::ClusterPointIndicesDecomposer::ClusterPointIndicesDecomposer
ClusterPointIndicesDecomposer()
Definition: cluster_point_indices_decomposer.h:135
jsk_pcl_ros::ClusterPointIndicesDecomposer::updateDiagnostic
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
Definition: cluster_point_indices_decomposer_nodelet.cpp:328
jsk_pcl_ros::ClusterPointIndicesDecomposer::sub_polygons_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
Definition: cluster_point_indices_decomposer.h:226
jsk_pcl_ros::ClusterPointIndicesDecomposer::findNearestPlane
virtual int findNearestPlane(const Eigen::Vector4f &center, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients)
Definition: cluster_point_indices_decomposer_nodelet.cpp:348
jsk_pcl_ros::ClusterPointIndicesDecomposerZAxis::onInit
virtual void onInit()
Definition: cluster_point_indices_decomposer_nodelet.cpp:92
jsk_pcl_ros::ClusterPointIndicesDecomposer::publishers_
std::vector< ros::Publisher > publishers_
Definition: cluster_point_indices_decomposer.h:232
jsk_pcl_ros::ClusterPointIndicesDecomposer::allocatePublishers
virtual void allocatePublishers(size_t num)
Definition: cluster_point_indices_decomposer_nodelet.cpp:863
attention_pose_set.r
r
Definition: attention_pose_set.py:9
jsk_pcl_ros::ClusterPointIndicesDecomposer::cluster_counter_
jsk_recognition_utils::Counter cluster_counter_
Definition: cluster_point_indices_decomposer.h:252
jsk_pcl_ros::ClusterPointIndicesDecomposer::queue_size_
int queue_size_
Definition: cluster_point_indices_decomposer.h:238
jsk_pcl_ros::ClusterPointIndicesDecomposer::extract
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)
Definition: cluster_point_indices_decomposer_nodelet.cpp:701
point
std::chrono::system_clock::time_point point
jsk_pcl_ros::ClusterPointIndicesDecomposer::transformPointCloudToAlignWithPlane
virtual bool transformPointCloudToAlignWithPlane(const pcl::PointCloud< pcl::PointXYZ >::Ptr segmented_cloud, pcl::PointCloud< pcl::PointXYZ >::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)
Definition: cluster_point_indices_decomposer_nodelet.cpp:375
jsk_pcl_ros::ClusterPointIndicesDecomposer::mask_pub_
ros::Publisher mask_pub_
Definition: cluster_point_indices_decomposer.h:233
jsk_recognition_utils::Counter
jsk_pcl_ros::ClusterPointIndicesDecomposer::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: cluster_point_indices_decomposer.h:228
jsk_pcl_ros::ClusterPointIndicesDecomposer
Definition: cluster_point_indices_decomposer.h:100
jsk_pcl_ros::ClusterPointIndicesDecomposer::pc_pub_
ros::Publisher pc_pub_
Definition: cluster_point_indices_decomposer.h:233
names.h
jsk_pcl_ros::ClusterPointIndicesDecomposer::sortIndicesOrderByCloudSize
void sortIndicesOrderByCloudSize(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
Definition: cluster_point_indices_decomposer_nodelet.cpp:299
jsk_pcl_ros::ClusterPointIndicesDecomposer::sort_by_
std::string sort_by_
Definition: cluster_point_indices_decomposer.h:250
jsk_pcl_ros::ClusterPointIndicesDecomposer::unsubscribe
virtual void unsubscribe()
Definition: cluster_point_indices_decomposer_nodelet.cpp:210
jsk_pcl_ros::ClusterPointIndicesDecomposer::~ClusterPointIndicesDecomposer
virtual ~ClusterPointIndicesDecomposer()
Definition: cluster_point_indices_decomposer_nodelet.cpp:98
jsk_pcl_ros::ClusterPointIndicesDecomposer::colorRGBAToUInt32
static uint32_t colorRGBAToUInt32(std_msgs::ColorRGBA c)
Definition: cluster_point_indices_decomposer.h:215
pcl_util.h
jsk_pcl_ros::ClusterPointIndicesDecomposer::negative_indices_pub_
ros::Publisher negative_indices_pub_
Definition: cluster_point_indices_decomposer.h:233
jsk_pcl_ros::ClusterPointIndicesDecomposer::sync_align_
boost::shared_ptr< message_filters::Synchronizer< SyncAlignPolicy > > sync_align_
Definition: cluster_point_indices_decomposer.h:230
jsk_pcl_ros::ClusterPointIndicesDecomposer::box_pub_
ros::Publisher box_pub_
Definition: cluster_point_indices_decomposer.h:233
tf::TransformListener
jsk_pcl_ros::ClusterPointIndicesDecomposer::publish_tf_
bool publish_tf_
Definition: cluster_point_indices_decomposer.h:241
synchronizer.h
diagnostic_updater::DiagnosticStatusWrapper
jsk_pcl_ros::ClusterPointIndicesDecomposer::force_to_flip_z_axis_
bool force_to_flip_z_axis_
Definition: cluster_point_indices_decomposer.h:239
mutex
boost::mutex mutex
global mutex.
Definition: depth_camera_error_visualization.cpp:86
jsk_pcl_ros::ClusterPointIndicesDecomposer::sortIndicesOrder
virtual void sortIndicesOrder(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
Definition: cluster_point_indices_decomposer_nodelet.cpp:220
jsk_pcl_ros::ClusterPointIndicesDecomposer::max_size_
int max_size_
Definition: cluster_point_indices_decomposer.h:248
jsk_pcl_ros::ClusterPointIndicesDecomposer::ApproximateSyncPolicy
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > ApproximateSyncPolicy
Definition: cluster_point_indices_decomposer.h:143
jsk_pcl_ros::ClusterPointIndicesDecomposer::use_pca_
bool use_pca_
Definition: cluster_point_indices_decomposer.h:246
jsk_pcl_ros::ClusterPointIndicesDecomposer::sortIndicesOrderByIndices
void sortIndicesOrderByIndices(const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
Definition: cluster_point_indices_decomposer_nodelet.cpp:257
jsk_pcl_ros::ClusterPointIndicesDecomposer::publishNegativeIndices
virtual void publishNegativeIndices(const sensor_msgs::PointCloud2ConstPtr &input, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
Definition: cluster_point_indices_decomposer_nodelet.cpp:674
jsk_pcl_ros::ClusterPointIndicesDecomposer::centers_pub_
ros::Publisher centers_pub_
Definition: cluster_point_indices_decomposer.h:233
tf_listener_singleton.h
jsk_pcl_ros::ClusterPointIndicesDecomposer::onInit
virtual void onInit()
Definition: cluster_point_indices_decomposer_nodelet.cpp:112
depth_error_calibration.input
input
Definition: depth_error_calibration.py:43
message_filters::sync_policies::ExactTime
jsk_pcl_ros::ClusterPointIndicesDecomposer::align_boxes_with_plane_
bool align_boxes_with_plane_
Definition: cluster_point_indices_decomposer.h:243
jsk_pcl_ros::ClusterPointIndicesDecomposer::SyncPolicy
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
Definition: cluster_point_indices_decomposer.h:140
jsk_pcl_ros::ClusterPointIndicesDecomposer::Config
jsk_pcl_ros::ClusterPointIndicesDecomposerConfig Config
Definition: cluster_point_indices_decomposer.h:137
jsk_pcl_ros::ClusterPointIndicesDecomposer::sub_input_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
Definition: cluster_point_indices_decomposer.h:224
jsk_pcl_ros::ClusterPointIndicesDecomposer::fill_boxes_label_with_nearest_plane_index_
bool fill_boxes_label_with_nearest_plane_index_
Definition: cluster_point_indices_decomposer.h:247


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:44