#include <simple_segmentation_nodelet.h>
Public Types | |
typedef FastSegmentation < pcl::PointXYZRGB, pcl::Normal, PointLabel > ::ClusterPtr | ClusterPtr |
typedef pcl::PointCloud < PointLabel > | LabelCloud |
typedef pcl::PointCloud < pcl::Normal > | NormalCloud |
typedef pcl::PointCloud < pcl::PointXYZRGB > | PointCloud |
Public Member Functions | |
SimpleSegmentationNodelet () | |
~SimpleSegmentationNodelet () | |
Protected Member Functions | |
void | actionCallback (const cob_3d_mapping_msgs::TriggerGoalConstPtr &goal) |
void | computeAndPublish () |
void | computeTexture (ClusterPtr &c, Eigen::Affine3f &trf, unsigned int id) |
void | configCallback (cob_3d_segmentation::segmentation_nodeletConfig &config, uint32_t levels) |
void | onInit () |
void | publishClassifiedCloud () |
void | topicCallback (const PointCloud::ConstPtr &cloud) |
Protected Attributes | |
actionlib::SimpleActionServer < cob_3d_mapping_msgs::TriggerAction > * | as_ |
float | centroid_passthrough_ |
bool | colorize_ |
boost::shared_ptr < dynamic_reconfigure::Server < cob_3d_segmentation::segmentation_nodeletConfig > > | config_server_ |
ClusterConversion < pcl::PointXYZRGB > | conv_ |
PointCloud::Ptr | down_ |
bool | downsample_ |
bool | enable_action_mode_ |
bool | filter_ |
bool | is_running_ |
LabelCloud::Ptr | labels_ |
int | min_cluster_size_ |
boost::mutex | mutex_ |
ros::NodeHandle | nh_ |
NormalCloud::Ptr | normals_ |
cob_3d_features::OrganizedNormalEstimationOMP < pcl::PointXYZRGB, pcl::Normal, PointLabel > | one_ |
ros::Publisher | pub_classified_ |
ros::Publisher | pub_segmented_ |
ros::Publisher | pub_shape_array_ |
FastSegmentation < pcl::PointXYZRGB, pcl::Normal, PointLabel > | seg_ |
PointCloud::Ptr | segmented_ |
ros::Subscriber | sub_points_ |
Definition at line 90 of file simple_segmentation_nodelet.h.
typedef FastSegmentation<pcl::PointXYZRGB, pcl::Normal, PointLabel>::ClusterPtr cob_3d_segmentation::SimpleSegmentationNodelet::ClusterPtr |
Definition at line 96 of file simple_segmentation_nodelet.h.
Definition at line 95 of file simple_segmentation_nodelet.h.
typedef pcl::PointCloud<pcl::Normal> cob_3d_segmentation::SimpleSegmentationNodelet::NormalCloud |
Definition at line 94 of file simple_segmentation_nodelet.h.
typedef pcl::PointCloud<pcl::PointXYZRGB> cob_3d_segmentation::SimpleSegmentationNodelet::PointCloud |
Definition at line 93 of file simple_segmentation_nodelet.h.
Definition at line 99 of file simple_segmentation_nodelet.h.
Definition at line 115 of file simple_segmentation_nodelet.h.
void cob_3d_segmentation::SimpleSegmentationNodelet::actionCallback | ( | const cob_3d_mapping_msgs::TriggerGoalConstPtr & | goal | ) | [protected] |
Definition at line 133 of file simple_segmentation_nodelet.cpp.
void cob_3d_segmentation::SimpleSegmentationNodelet::computeAndPublish | ( | ) | [protected] |
Definition at line 180 of file simple_segmentation_nodelet.cpp.
void cob_3d_segmentation::SimpleSegmentationNodelet::computeTexture | ( | ClusterPtr & | c, |
Eigen::Affine3f & | trf, | ||
unsigned int | id | ||
) | [protected] |
Definition at line 282 of file simple_segmentation_nodelet.cpp.
void cob_3d_segmentation::SimpleSegmentationNodelet::configCallback | ( | cob_3d_segmentation::segmentation_nodeletConfig & | config, |
uint32_t | levels | ||
) | [protected] |
Definition at line 113 of file simple_segmentation_nodelet.cpp.
void cob_3d_segmentation::SimpleSegmentationNodelet::onInit | ( | ) | [protected, virtual] |
Implements nodelet::Nodelet.
Definition at line 84 of file simple_segmentation_nodelet.cpp.
void cob_3d_segmentation::SimpleSegmentationNodelet::publishClassifiedCloud | ( | ) | [protected] |
Definition at line 235 of file simple_segmentation_nodelet.cpp.
void cob_3d_segmentation::SimpleSegmentationNodelet::topicCallback | ( | const PointCloud::ConstPtr & | cloud | ) | [protected] |
Definition at line 155 of file simple_segmentation_nodelet.cpp.
actionlib::SimpleActionServer<cob_3d_mapping_msgs::TriggerAction>* cob_3d_segmentation::SimpleSegmentationNodelet::as_ [protected] |
Definition at line 135 of file simple_segmentation_nodelet.h.
float cob_3d_segmentation::SimpleSegmentationNodelet::centroid_passthrough_ [protected] |
Definition at line 148 of file simple_segmentation_nodelet.h.
bool cob_3d_segmentation::SimpleSegmentationNodelet::colorize_ [protected] |
Definition at line 152 of file simple_segmentation_nodelet.h.
boost::shared_ptr<dynamic_reconfigure::Server<cob_3d_segmentation::segmentation_nodeletConfig> > cob_3d_segmentation::SimpleSegmentationNodelet::config_server_ [protected] |
Definition at line 137 of file simple_segmentation_nodelet.h.
ClusterConversion<pcl::PointXYZRGB> cob_3d_segmentation::SimpleSegmentationNodelet::conv_ [protected] |
Definition at line 141 of file simple_segmentation_nodelet.h.
PointCloud::Ptr cob_3d_segmentation::SimpleSegmentationNodelet::down_ [protected] |
Definition at line 143 of file simple_segmentation_nodelet.h.
bool cob_3d_segmentation::SimpleSegmentationNodelet::downsample_ [protected] |
Definition at line 151 of file simple_segmentation_nodelet.h.
bool cob_3d_segmentation::SimpleSegmentationNodelet::enable_action_mode_ [protected] |
Definition at line 153 of file simple_segmentation_nodelet.h.
bool cob_3d_segmentation::SimpleSegmentationNodelet::filter_ [protected] |
Definition at line 150 of file simple_segmentation_nodelet.h.
bool cob_3d_segmentation::SimpleSegmentationNodelet::is_running_ [protected] |
Definition at line 154 of file simple_segmentation_nodelet.h.
LabelCloud::Ptr cob_3d_segmentation::SimpleSegmentationNodelet::labels_ [protected] |
Definition at line 146 of file simple_segmentation_nodelet.h.
Definition at line 149 of file simple_segmentation_nodelet.h.
boost::mutex cob_3d_segmentation::SimpleSegmentationNodelet::mutex_ [protected] |
Definition at line 128 of file simple_segmentation_nodelet.h.
Reimplemented from nodelet::Nodelet.
Definition at line 130 of file simple_segmentation_nodelet.h.
NormalCloud::Ptr cob_3d_segmentation::SimpleSegmentationNodelet::normals_ [protected] |
Definition at line 145 of file simple_segmentation_nodelet.h.
cob_3d_features::OrganizedNormalEstimationOMP<pcl::PointXYZRGB, pcl::Normal, PointLabel> cob_3d_segmentation::SimpleSegmentationNodelet::one_ [protected] |
Definition at line 139 of file simple_segmentation_nodelet.h.
Definition at line 133 of file simple_segmentation_nodelet.h.
Definition at line 132 of file simple_segmentation_nodelet.h.
Definition at line 134 of file simple_segmentation_nodelet.h.
FastSegmentation<pcl::PointXYZRGB, pcl::Normal, PointLabel> cob_3d_segmentation::SimpleSegmentationNodelet::seg_ [protected] |
Definition at line 140 of file simple_segmentation_nodelet.h.
PointCloud::Ptr cob_3d_segmentation::SimpleSegmentationNodelet::segmented_ [protected] |
Definition at line 144 of file simple_segmentation_nodelet.h.
Definition at line 131 of file simple_segmentation_nodelet.h.