#include <cluster_point_indices_decomposer.h>
|
| 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 () |
|
|
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 ¢er_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 ¢er, 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) |
|
◆ ApproximateSyncAlignPolicy
◆ ApproximateSyncPolicy
◆ Config
◆ SyncAlignPolicy
◆ SyncPolicy
◆ ClusterPointIndicesDecomposer()
jsk_pcl_ros::ClusterPointIndicesDecomposer::ClusterPointIndicesDecomposer |
( |
| ) |
|
|
inline |
◆ ~ClusterPointIndicesDecomposer()
jsk_pcl_ros::ClusterPointIndicesDecomposer::~ClusterPointIndicesDecomposer |
( |
| ) |
|
|
virtual |
◆ 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 |
◆ 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()
◆ align_boxes_
bool jsk_pcl_ros::ClusterPointIndicesDecomposer::align_boxes_ |
|
protected |
◆ align_boxes_with_plane_
bool jsk_pcl_ros::ClusterPointIndicesDecomposer::align_boxes_with_plane_ |
|
protected |
◆ async_
◆ async_align_
◆ box_pub_
◆ br_
◆ centers_pub_
ros::Publisher jsk_pcl_ros::ClusterPointIndicesDecomposer::centers_pub_ |
|
protected |
◆ cluster_counter_
◆ fill_boxes_label_with_nearest_plane_index_
bool jsk_pcl_ros::ClusterPointIndicesDecomposer::fill_boxes_label_with_nearest_plane_index_ |
|
protected |
◆ force_to_flip_z_axis_
bool jsk_pcl_ros::ClusterPointIndicesDecomposer::force_to_flip_z_axis_ |
|
protected |
◆ indices_pub_
ros::Publisher jsk_pcl_ros::ClusterPointIndicesDecomposer::indices_pub_ |
|
protected |
◆ label_pub_
◆ mask_pub_
◆ max_size_
int jsk_pcl_ros::ClusterPointIndicesDecomposer::max_size_ |
|
protected |
◆ min_size_
int jsk_pcl_ros::ClusterPointIndicesDecomposer::min_size_ |
|
protected |
◆ mutex_
boost::mutex jsk_pcl_ros::ClusterPointIndicesDecomposer::mutex_ |
|
protected |
◆ negative_indices_pub_
ros::Publisher jsk_pcl_ros::ClusterPointIndicesDecomposer::negative_indices_pub_ |
|
protected |
◆ pc_pub_
◆ publish_clouds_
bool jsk_pcl_ros::ClusterPointIndicesDecomposer::publish_clouds_ |
|
protected |
◆ publish_tf_
bool jsk_pcl_ros::ClusterPointIndicesDecomposer::publish_tf_ |
|
protected |
◆ publishers_
◆ queue_size_
int jsk_pcl_ros::ClusterPointIndicesDecomposer::queue_size_ |
|
protected |
◆ sort_by_
std::string jsk_pcl_ros::ClusterPointIndicesDecomposer::sort_by_ |
|
protected |
◆ srv_
◆ sub_coefficients_
message_filters::Subscriber<jsk_recognition_msgs::ModelCoefficientsArray> jsk_pcl_ros::ClusterPointIndicesDecomposer::sub_coefficients_ |
|
protected |
◆ sub_input_
◆ sub_polygons_
◆ sub_target_
◆ sync_
◆ sync_align_
◆ target_frame_id_
std::string jsk_pcl_ros::ClusterPointIndicesDecomposer::target_frame_id_ |
|
protected |
◆ tf_listener_
◆ tf_prefix_
std::string jsk_pcl_ros::ClusterPointIndicesDecomposer::tf_prefix_ |
|
protected |
◆ use_async_
bool jsk_pcl_ros::ClusterPointIndicesDecomposer::use_async_ |
|
protected |
◆ use_pca_
bool jsk_pcl_ros::ClusterPointIndicesDecomposer::use_pca_ |
|
protected |
The documentation for this class was generated from the following files: