Public Types | Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::ClusterPointIndicesDecomposer Class Reference

#include <cluster_point_indices_decomposer.h>

Inheritance diagram for jsk_pcl_ros::ClusterPointIndicesDecomposer:
Inheritance graph
[legend]

Public Types

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > ApproximateSyncAlignPolicy
 
typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > ApproximateSyncPolicy
 
typedef jsk_pcl_ros::ClusterPointIndicesDecomposerConfig Config
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray > SyncAlignPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > SyncPolicy
 

Public Member Functions

 ClusterPointIndicesDecomposer ()
 
virtual void extract (const sensor_msgs::PointCloud2ConstPtr &point, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices)
 
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)
 
virtual void onInit ()
 
virtual void sortIndicesOrder (const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
 
void sortIndicesOrderByCloudSize (const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
 
void sortIndicesOrderByIndices (const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
 
void sortIndicesOrderByZAxis (const pcl::PointCloud< pcl::PointXYZ >::Ptr input, const std::vector< pcl::IndicesPtr > indices_array, std::vector< size_t > *argsort)
 
virtual ~ClusterPointIndicesDecomposer ()
 

Protected Member Functions

void addToDebugPointCloud (const pcl::PointCloud< pcl::PointXYZ >::Ptr segmented_cloud, size_t i, pcl::PointCloud< pcl::PointXYZRGB > &debug_output)
 
virtual void allocatePublishers (size_t num)
 
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)
 
virtual void configCallback (Config &config, uint32_t level)
 
virtual int findNearestPlane (const Eigen::Vector4f &center, const jsk_recognition_msgs::PolygonArrayConstPtr &planes, const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &coefficients)
 
virtual void publishNegativeIndices (const sensor_msgs::PointCloud2ConstPtr &input, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices_input)
 
virtual void subscribe ()
 
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)
 
virtual void unsubscribe ()
 
virtual void updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat)
 

Static Protected Member Functions

static uint32_t colorRGBAToUInt32 (std_msgs::ColorRGBA c)
 

Protected Attributes

bool align_boxes_
 
bool align_boxes_with_plane_
 
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
 
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncAlignPolicy > > async_align_
 
ros::Publisher box_pub_
 
boost::shared_ptr< tf::TransformBroadcasterbr_
 
ros::Publisher centers_pub_
 
jsk_recognition_utils::Counter cluster_counter_
 
bool fill_boxes_label_with_nearest_plane_index_
 
bool force_to_flip_z_axis_
 
ros::Publisher indices_pub_
 
ros::Publisher label_pub_
 
ros::Publisher mask_pub_
 
int max_size_
 
int min_size_
 
boost::mutex mutex_
 
ros::Publisher negative_indices_pub_
 
ros::Publisher pc_pub_
 
bool publish_clouds_
 
bool publish_tf_
 
std::vector< ros::Publisherpublishers_
 
int queue_size_
 
std::string sort_by_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
message_filters::Subscriber< jsk_recognition_msgs::ModelCoefficientsArray > sub_coefficients_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
 
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
 
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_target_
 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
 
boost::shared_ptr< message_filters::Synchronizer< SyncAlignPolicy > > sync_align_
 
std::string target_frame_id_
 
tf::TransformListenertf_listener_
 
std::string tf_prefix_
 
bool use_async_
 
bool use_pca_
 

Detailed Description

Definition at line 100 of file cluster_point_indices_decomposer.h.

Member Typedef Documentation

◆ ApproximateSyncAlignPolicy

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray> jsk_pcl_ros::ClusterPointIndicesDecomposer::ApproximateSyncAlignPolicy

Definition at line 153 of file cluster_point_indices_decomposer.h.

◆ ApproximateSyncPolicy

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > jsk_pcl_ros::ClusterPointIndicesDecomposer::ApproximateSyncPolicy

Definition at line 143 of file cluster_point_indices_decomposer.h.

◆ Config

typedef jsk_pcl_ros::ClusterPointIndicesDecomposerConfig jsk_pcl_ros::ClusterPointIndicesDecomposer::Config

Definition at line 137 of file cluster_point_indices_decomposer.h.

◆ SyncAlignPolicy

typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray, jsk_recognition_msgs::ModelCoefficientsArray> jsk_pcl_ros::ClusterPointIndicesDecomposer::SyncAlignPolicy

Definition at line 148 of file cluster_point_indices_decomposer.h.

◆ SyncPolicy

typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > jsk_pcl_ros::ClusterPointIndicesDecomposer::SyncPolicy

Definition at line 140 of file cluster_point_indices_decomposer.h.

Constructor & Destructor Documentation

◆ ClusterPointIndicesDecomposer()

jsk_pcl_ros::ClusterPointIndicesDecomposer::ClusterPointIndicesDecomposer ( )
inline

Definition at line 135 of file cluster_point_indices_decomposer.h.

◆ ~ClusterPointIndicesDecomposer()

jsk_pcl_ros::ClusterPointIndicesDecomposer::~ClusterPointIndicesDecomposer ( )
virtual

Definition at line 98 of file cluster_point_indices_decomposer_nodelet.cpp.

Member Function Documentation

◆ addToDebugPointCloud()

void jsk_pcl_ros::ClusterPointIndicesDecomposer::addToDebugPointCloud ( const pcl::PointCloud< pcl::PointXYZ >::Ptr  segmented_cloud,
size_t  i,
pcl::PointCloud< pcl::PointXYZRGB > &  debug_output 
)
protected

◆ allocatePublishers()

void jsk_pcl_ros::ClusterPointIndicesDecomposer::allocatePublishers ( size_t  num)
protectedvirtual

◆ colorRGBAToUInt32()

static uint32_t jsk_pcl_ros::ClusterPointIndicesDecomposer::colorRGBAToUInt32 ( std_msgs::ColorRGBA  c)
inlinestaticprotected

Definition at line 215 of file cluster_point_indices_decomposer.h.

◆ computeCenterAndBoundingBox()

bool jsk_pcl_ros::ClusterPointIndicesDecomposer::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 
)
protectedvirtual

◆ configCallback()

void jsk_pcl_ros::ClusterPointIndicesDecomposer::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

◆ extract() [1/2]

void jsk_pcl_ros::ClusterPointIndicesDecomposer::extract ( const sensor_msgs::PointCloud2ConstPtr &  point,
const jsk_recognition_msgs::ClusterPointIndicesConstPtr &  indices 
)
virtual

◆ extract() [2/2]

void jsk_pcl_ros::ClusterPointIndicesDecomposer::extract ( const sensor_msgs::PointCloud2ConstPtr &  point,
const jsk_recognition_msgs::ClusterPointIndicesConstPtr &  indices,
const jsk_recognition_msgs::PolygonArrayConstPtr &  planes,
const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &  coefficients 
)
virtual

◆ findNearestPlane()

int jsk_pcl_ros::ClusterPointIndicesDecomposer::findNearestPlane ( const Eigen::Vector4f &  center,
const jsk_recognition_msgs::PolygonArrayConstPtr &  planes,
const jsk_recognition_msgs::ModelCoefficientsArrayConstPtr &  coefficients 
)
protectedvirtual

◆ onInit()

void jsk_pcl_ros::ClusterPointIndicesDecomposer::onInit ( )
virtual

◆ publishNegativeIndices()

void jsk_pcl_ros::ClusterPointIndicesDecomposer::publishNegativeIndices ( const sensor_msgs::PointCloud2ConstPtr &  input,
const jsk_recognition_msgs::ClusterPointIndicesConstPtr &  indices_input 
)
protectedvirtual

◆ sortIndicesOrder()

void jsk_pcl_ros::ClusterPointIndicesDecomposer::sortIndicesOrder ( const pcl::PointCloud< pcl::PointXYZ >::Ptr  input,
const std::vector< pcl::IndicesPtr >  indices_array,
std::vector< size_t > *  argsort 
)
virtual

◆ sortIndicesOrderByCloudSize()

void jsk_pcl_ros::ClusterPointIndicesDecomposer::sortIndicesOrderByCloudSize ( const pcl::PointCloud< pcl::PointXYZ >::Ptr  input,
const std::vector< pcl::IndicesPtr >  indices_array,
std::vector< size_t > *  argsort 
)

◆ sortIndicesOrderByIndices()

void jsk_pcl_ros::ClusterPointIndicesDecomposer::sortIndicesOrderByIndices ( const pcl::PointCloud< pcl::PointXYZ >::Ptr  input,
const std::vector< pcl::IndicesPtr >  indices_array,
std::vector< size_t > *  argsort 
)

◆ sortIndicesOrderByZAxis()

void jsk_pcl_ros::ClusterPointIndicesDecomposer::sortIndicesOrderByZAxis ( const pcl::PointCloud< pcl::PointXYZ >::Ptr  input,
const std::vector< pcl::IndicesPtr >  indices_array,
std::vector< size_t > *  argsort 
)

◆ subscribe()

void jsk_pcl_ros::ClusterPointIndicesDecomposer::subscribe ( )
protectedvirtual

◆ transformPointCloudToAlignWithPlane()

bool jsk_pcl_ros::ClusterPointIndicesDecomposer::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 
)
protectedvirtual

◆ unsubscribe()

void jsk_pcl_ros::ClusterPointIndicesDecomposer::unsubscribe ( )
protectedvirtual

◆ updateDiagnostic()

void jsk_pcl_ros::ClusterPointIndicesDecomposer::updateDiagnostic ( diagnostic_updater::DiagnosticStatusWrapper stat)
protectedvirtual

Member Data Documentation

◆ align_boxes_

bool jsk_pcl_ros::ClusterPointIndicesDecomposer::align_boxes_
protected

Definition at line 242 of file cluster_point_indices_decomposer.h.

◆ align_boxes_with_plane_

bool jsk_pcl_ros::ClusterPointIndicesDecomposer::align_boxes_with_plane_
protected

Definition at line 243 of file cluster_point_indices_decomposer.h.

◆ async_

boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncPolicy> > jsk_pcl_ros::ClusterPointIndicesDecomposer::async_
protected

Definition at line 229 of file cluster_point_indices_decomposer.h.

◆ async_align_

boost::shared_ptr<message_filters::Synchronizer<ApproximateSyncAlignPolicy> > jsk_pcl_ros::ClusterPointIndicesDecomposer::async_align_
protected

Definition at line 231 of file cluster_point_indices_decomposer.h.

◆ box_pub_

ros::Publisher jsk_pcl_ros::ClusterPointIndicesDecomposer::box_pub_
protected

Definition at line 233 of file cluster_point_indices_decomposer.h.

◆ br_

boost::shared_ptr<tf::TransformBroadcaster> jsk_pcl_ros::ClusterPointIndicesDecomposer::br_
protected

Definition at line 234 of file cluster_point_indices_decomposer.h.

◆ centers_pub_

ros::Publisher jsk_pcl_ros::ClusterPointIndicesDecomposer::centers_pub_
protected

Definition at line 233 of file cluster_point_indices_decomposer.h.

◆ cluster_counter_

jsk_recognition_utils::Counter jsk_pcl_ros::ClusterPointIndicesDecomposer::cluster_counter_
protected

Definition at line 252 of file cluster_point_indices_decomposer.h.

◆ fill_boxes_label_with_nearest_plane_index_

bool jsk_pcl_ros::ClusterPointIndicesDecomposer::fill_boxes_label_with_nearest_plane_index_
protected

Definition at line 247 of file cluster_point_indices_decomposer.h.

◆ force_to_flip_z_axis_

bool jsk_pcl_ros::ClusterPointIndicesDecomposer::force_to_flip_z_axis_
protected

Definition at line 239 of file cluster_point_indices_decomposer.h.

◆ indices_pub_

ros::Publisher jsk_pcl_ros::ClusterPointIndicesDecomposer::indices_pub_
protected

Definition at line 233 of file cluster_point_indices_decomposer.h.

◆ label_pub_

ros::Publisher jsk_pcl_ros::ClusterPointIndicesDecomposer::label_pub_
protected

Definition at line 233 of file cluster_point_indices_decomposer.h.

◆ mask_pub_

ros::Publisher jsk_pcl_ros::ClusterPointIndicesDecomposer::mask_pub_
protected

Definition at line 233 of file cluster_point_indices_decomposer.h.

◆ max_size_

int jsk_pcl_ros::ClusterPointIndicesDecomposer::max_size_
protected

Definition at line 248 of file cluster_point_indices_decomposer.h.

◆ min_size_

int jsk_pcl_ros::ClusterPointIndicesDecomposer::min_size_
protected

Definition at line 249 of file cluster_point_indices_decomposer.h.

◆ mutex_

boost::mutex jsk_pcl_ros::ClusterPointIndicesDecomposer::mutex_
protected

Definition at line 175 of file cluster_point_indices_decomposer.h.

◆ negative_indices_pub_

ros::Publisher jsk_pcl_ros::ClusterPointIndicesDecomposer::negative_indices_pub_
protected

Definition at line 233 of file cluster_point_indices_decomposer.h.

◆ pc_pub_

ros::Publisher jsk_pcl_ros::ClusterPointIndicesDecomposer::pc_pub_
protected

Definition at line 233 of file cluster_point_indices_decomposer.h.

◆ publish_clouds_

bool jsk_pcl_ros::ClusterPointIndicesDecomposer::publish_clouds_
protected

Definition at line 240 of file cluster_point_indices_decomposer.h.

◆ publish_tf_

bool jsk_pcl_ros::ClusterPointIndicesDecomposer::publish_tf_
protected

Definition at line 241 of file cluster_point_indices_decomposer.h.

◆ publishers_

std::vector<ros::Publisher> jsk_pcl_ros::ClusterPointIndicesDecomposer::publishers_
protected

Definition at line 232 of file cluster_point_indices_decomposer.h.

◆ queue_size_

int jsk_pcl_ros::ClusterPointIndicesDecomposer::queue_size_
protected

Definition at line 238 of file cluster_point_indices_decomposer.h.

◆ sort_by_

std::string jsk_pcl_ros::ClusterPointIndicesDecomposer::sort_by_
protected

Definition at line 250 of file cluster_point_indices_decomposer.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::ClusterPointIndicesDecomposer::srv_
protected

Definition at line 174 of file cluster_point_indices_decomposer.h.

◆ sub_coefficients_

message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> jsk_pcl_ros::ClusterPointIndicesDecomposer::sub_coefficients_
protected

Definition at line 227 of file cluster_point_indices_decomposer.h.

◆ sub_input_

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::ClusterPointIndicesDecomposer::sub_input_
protected

Definition at line 224 of file cluster_point_indices_decomposer.h.

◆ sub_polygons_

message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> jsk_pcl_ros::ClusterPointIndicesDecomposer::sub_polygons_
protected

Definition at line 226 of file cluster_point_indices_decomposer.h.

◆ sub_target_

message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> jsk_pcl_ros::ClusterPointIndicesDecomposer::sub_target_
protected

Definition at line 225 of file cluster_point_indices_decomposer.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::ClusterPointIndicesDecomposer::sync_
protected

Definition at line 228 of file cluster_point_indices_decomposer.h.

◆ sync_align_

boost::shared_ptr<message_filters::Synchronizer<SyncAlignPolicy> > jsk_pcl_ros::ClusterPointIndicesDecomposer::sync_align_
protected

Definition at line 230 of file cluster_point_indices_decomposer.h.

◆ target_frame_id_

std::string jsk_pcl_ros::ClusterPointIndicesDecomposer::target_frame_id_
protected

Definition at line 244 of file cluster_point_indices_decomposer.h.

◆ tf_listener_

tf::TransformListener* jsk_pcl_ros::ClusterPointIndicesDecomposer::tf_listener_
protected

Definition at line 245 of file cluster_point_indices_decomposer.h.

◆ tf_prefix_

std::string jsk_pcl_ros::ClusterPointIndicesDecomposer::tf_prefix_
protected

Definition at line 235 of file cluster_point_indices_decomposer.h.

◆ use_async_

bool jsk_pcl_ros::ClusterPointIndicesDecomposer::use_async_
protected

Definition at line 237 of file cluster_point_indices_decomposer.h.

◆ use_pca_

bool jsk_pcl_ros::ClusterPointIndicesDecomposer::use_pca_
protected

Definition at line 246 of file cluster_point_indices_decomposer.h.


The documentation for this class was generated from the following files:


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