#include <convex_connected_voxels.h>
|
typedef pcl::PointXYZRGB | PointT |
|
|
void | cloud_cb (const sensor_msgs::PointCloud2::ConstPtr &) |
|
void | estimatePointCloudNormals (const pcl::PointCloud< PointT >::Ptr, pcl::PointCloud< pcl::Normal >::Ptr, const int=8, const double=0.02, bool=true) |
|
void | getConvexLabelCloudIndices (const std::vector< pcl::PointCloud< PointT >::Ptr > &, pcl::PointCloud< PointT >::Ptr, const std::vector< int > &, std::map< int, pcl::PointIndices > &) |
|
void | indices_cb (const jsk_recognition_msgs::ClusterPointIndices &) |
|
void | nearestNeigborSearch (pcl::PointCloud< pcl::PointXYZ >::Ptr, std::vector< std::vector< int > > &, const int=8, const double=0.02, bool=true) |
|
virtual void | onInit () |
|
void | segmentCloud (const pcl::PointCloud< PointT >::Ptr, const std::vector< pcl::PointIndices > &, std::vector< pcl::PointCloud< PointT >::Ptr > &, std::vector< pcl::PointCloud< pcl::Normal >::Ptr > &, pcl::PointCloud< pcl::PointXYZ >::Ptr) |
|
virtual void | subscribe () |
|
virtual void | unsubscribe () |
|
Definition at line 114 of file convex_connected_voxels.h.
◆ PointT
◆ ConvexConnectedVoxels()
jsk_pcl_ros::ConvexConnectedVoxels::ConvexConnectedVoxels |
( |
| ) |
|
|
inline |
◆ cloud_cb()
void jsk_pcl_ros::ConvexConnectedVoxels::cloud_cb |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
cloud_msg | ) |
|
|
protected |
◆ estimatePointCloudNormals()
void jsk_pcl_ros::ConvexConnectedVoxels::estimatePointCloudNormals |
( |
const pcl::PointCloud< PointT >::Ptr |
cloud, |
|
|
pcl::PointCloud< pcl::Normal >::Ptr |
s_normal, |
|
|
const int |
k = 8 , |
|
|
const double |
radius = 0.02 , |
|
|
bool |
ksearch = true |
|
) |
| |
|
protected |
◆ getConvexLabelCloudIndices()
◆ indices_cb()
void jsk_pcl_ros::ConvexConnectedVoxels::indices_cb |
( |
const jsk_recognition_msgs::ClusterPointIndices & |
indices_msg | ) |
|
|
protected |
◆ nearestNeigborSearch()
void jsk_pcl_ros::ConvexConnectedVoxels::nearestNeigborSearch |
( |
pcl::PointCloud< pcl::PointXYZ >::Ptr |
cloud, |
|
|
std::vector< std::vector< int > > & |
pointIndices, |
|
|
const int |
k = 8 , |
|
|
const double |
radius = 0.02 , |
|
|
bool |
isneigbour = true |
|
) |
| |
|
protected |
◆ onInit()
void jsk_pcl_ros::ConvexConnectedVoxels::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ segmentCloud()
◆ subscribe()
void jsk_pcl_ros::ConvexConnectedVoxels::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::ConvexConnectedVoxels::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ indices_
std::vector<pcl::PointIndices> jsk_pcl_ros::ConvexConnectedVoxels::indices_ |
|
private |
◆ mutex_
◆ nh_
◆ pub_indices_
◆ sub_cloud_
◆ sub_indices_
The documentation for this class was generated from the following files: