Public Member Functions | Protected Member Functions | Protected Attributes | Private Types | Private Attributes | List of all members
pcl_ros::SACSegmentationFromNormals Class Reference

SACSegmentationFromNormals represents the PCL nodelet segmentation class for Sample Consensus methods and models that require the use of surface normals for estimation. More...

#include <sac_segmentation.h>

Inheritance diagram for pcl_ros::SACSegmentationFromNormals:
Inheritance graph
[legend]

Public Member Functions

std::string getInputTFframe ()
 Get the TF frame the input PointCloud should be transformed into before processing. More...
 
std::string getOutputTFframe ()
 Get the TF frame the PointCloud should be transformed into after processing. More...
 
void setInputTFframe (std::string tf_frame)
 Set the input TF frame the data should be transformed into before processing, if input.header.frame_id is different. More...
 
void setOutputTFframe (std::string tf_frame)
 Set the output TF frame the data should be transformed into after processing. More...
 
- Public Member Functions inherited from pcl_ros::SACSegmentation
std::string getInputTFframe ()
 Get the TF frame the input PointCloud should be transformed into before processing. More...
 
std::string getOutputTFframe ()
 Get the TF frame the PointCloud should be transformed into after processing. More...
 
 SACSegmentation ()
 Constructor. More...
 
void setInputTFframe (std::string tf_frame)
 Set the input TF frame the data should be transformed into before processing, if input.header.frame_id is different. More...
 
void setOutputTFframe (std::string tf_frame)
 Set the output TF frame the data should be transformed into after processing. More...
 
- Public Member Functions inherited from pcl_ros::PCLNodelet
 PCLNodelet ()
 Empty constructor. More...
 
- Public Member Functions inherited from nodelet_topic_tools::NodeletLazy
 NodeletLazy ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Protected Member Functions

void axis_callback (const pcl_msgs::ModelCoefficientsConstPtr &model)
 Model callback. More...
 
void config_callback (SACSegmentationFromNormalsConfig &config, uint32_t level)
 Dynamic reconfigure callback. More...
 
void input_callback (const PointCloudConstPtr &cloud)
 Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp. More...
 
void input_normals_indices_callback (const PointCloudConstPtr &cloud, const PointCloudNConstPtr &cloud_normals, const PointIndicesConstPtr &indices)
 Input point cloud callback. More...
 
virtual void onInit ()
 Nodelet initialization routine. More...
 
virtual void subscribe ()
 LazyNodelet connection routine. More...
 
virtual void unsubscribe ()
 
- Protected Member Functions inherited from pcl_ros::SACSegmentation
void config_callback (SACSegmentationConfig &config, uint32_t level)
 Dynamic reconfigure callback. More...
 
void indices_callback (const PointIndicesConstPtr &indices)
 Indices callback. Used when latched_indices_ is set. More...
 
void input_callback (const PointCloudConstPtr &input)
 Input callback. Used when latched_indices_ is set. More...
 
void input_indices_callback (const PointCloudConstPtr &cloud, const PointIndicesConstPtr &indices)
 Input point cloud callback. Used when use_indices is set. More...
 
- Protected Member Functions inherited from pcl_ros::PCLNodelet
bool isValid (const ModelCoefficientsConstPtr &, const std::string &="model")
 Test whether a given ModelCoefficients message is "valid" (i.e., has values). More...
 
bool isValid (const PointCloud2::ConstPtr &cloud, const std::string &topic_name="input")
 Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero). More...
 
bool isValid (const PointCloudConstPtr &cloud, const std::string &topic_name="input")
 Test whether a given PointCloud message is "valid" (i.e., has points, and width and height are non-zero). More...
 
bool isValid (const PointIndicesConstPtr &, const std::string &="indices")
 Test whether a given PointIndices message is "valid" (i.e., has values). More...
 
- Protected Member Functions inherited from nodelet_topic_tools::NodeletLazy
ros::Publisher advertise (ros::NodeHandle &nh, std::string topic, int queue_size, bool latch=false)
 
virtual void connectionCallback (const ros::SingleSubscriberPublisher &pub)
 
virtual void onInitPostProcess ()
 
virtual void warnNeverSubscribedCallback (const ros::WallTimerEvent &event)
 
- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Protected Attributes

message_filters::PassThrough< PointIndicesnf_
 Null passthrough filter, used for pushing empty elements in the synchronizer. More...
 
boost::shared_ptr< dynamic_reconfigure::Server< SACSegmentationFromNormalsConfig > > srv_
 Pointer to a dynamic reconfigure service. More...
 
ros::Subscriber sub_axis_
 The input PointCloud subscriber. More...
 
message_filters::Subscriber< PointCloudNsub_normals_filter_
 The normals PointCloud subscriber filter. More...
 
std::string tf_input_frame_
 The input TF frame the data should be transformed into, if input.header.frame_id is different. More...
 
std::string tf_input_orig_frame_
 The original data input TF frame. More...
 
std::string tf_output_frame_
 The output TF frame the data should be transformed into, if input.header.frame_id is different. More...
 
- Protected Attributes inherited from pcl_ros::SACSegmentation
PointIndices indices_
 Pointer to a set of indices stored internally. (used when latched_indices_ is set). More...
 
int min_inliers_
 
message_filters::PassThrough< pcl_msgs::PointIndices > nf_pi_
 Null passthrough filter, used for pushing empty elements in the synchronizer. More...
 
ros::Publisher pub_indices_
 The output PointIndices publisher. More...
 
ros::Publisher pub_model_
 The output ModelCoefficients publisher. More...
 
boost::shared_ptr< dynamic_reconfigure::Server< SACSegmentationConfig > > srv_
 Pointer to a dynamic reconfigure service. More...
 
ros::Subscriber sub_input_
 The input PointCloud subscriber. More...
 
std::string tf_input_frame_
 The input TF frame the data should be transformed into, if input.header.frame_id is different. More...
 
std::string tf_input_orig_frame_
 The original data input TF frame. More...
 
std::string tf_output_frame_
 The output TF frame the data should be transformed into, if input.header.frame_id is different. More...
 
- Protected Attributes inherited from pcl_ros::PCLNodelet
bool approximate_sync_
 True if we use an approximate time synchronizer versus an exact one (false by default). More...
 
bool latched_indices_
 Set to true if the indices topic is latched. More...
 
int max_queue_size_
 The maximum queue size (default: 3). More...
 
ros::Publisher pub_output_
 The output PointCloud publisher. More...
 
message_filters::Subscriber< PointIndicessub_indices_filter_
 The message filter subscriber for PointIndices. More...
 
message_filters::Subscriber< PointCloudsub_input_filter_
 The message filter subscriber for PointCloud2. More...
 
tf::TransformListener tf_listener_
 TF listener object. More...
 
bool use_indices_
 Set to true if point indices are used. More...
 
- Protected Attributes inherited from nodelet_topic_tools::NodeletLazy
boost::mutex connection_mutex_
 
ConnectionStatus connection_status_
 
bool ever_subscribed_
 
bool lazy_
 
boost::shared_ptr< ros::NodeHandlenh_
 
boost::shared_ptr< ros::NodeHandlepnh_
 
std::vector< ros::Publisherpublishers_
 
ros::WallTimer timer_ever_subscribed_
 
bool verbose_connection_
 

Private Types

typedef pcl::PointCloud< pcl::PointXYZ > PointCloud
 
typedef boost::shared_ptr< const PointCloudPointCloudConstPtr
 
typedef pcl::PointCloud< pcl::Normal > PointCloudN
 
typedef boost::shared_ptr< const PointCloudNPointCloudNConstPtr
 
typedef boost::shared_ptr< PointCloudNPointCloudNPtr
 
typedef boost::shared_ptr< PointCloudPointCloudPtr
 

Private Attributes

pcl::SACSegmentationFromNormals< pcl::PointXYZ, pcl::Normal > impl_
 The PCL implementation used. More...
 
boost::mutex mutex_
 Internal mutex. More...
 
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointCloudN, PointIndices > > > sync_input_normals_indices_a_
 Synchronized input, normals, and indices. More...
 
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointCloudN, PointIndices > > > sync_input_normals_indices_e_
 

Additional Inherited Members

- Public Types inherited from pcl_ros::PCLNodelet
typedef pcl::IndicesConstPtr IndicesConstPtr
 
typedef pcl::IndicesPtr IndicesPtr
 
typedef pcl_msgs::ModelCoefficients ModelCoefficients
 
typedef ModelCoefficients::ConstPtr ModelCoefficientsConstPtr
 
typedef ModelCoefficients::Ptr ModelCoefficientsPtr
 
typedef pcl::PointCloud< pcl::PointXYZ > PointCloud
 
typedef sensor_msgs::PointCloud2 PointCloud2
 
typedef boost::shared_ptr< const PointCloudPointCloudConstPtr
 
typedef boost::shared_ptr< PointCloudPointCloudPtr
 
typedef pcl_msgs::PointIndices PointIndices
 
typedef PointIndices::ConstPtr PointIndicesConstPtr
 
typedef PointIndices::Ptr PointIndicesPtr
 

Detailed Description

SACSegmentationFromNormals represents the PCL nodelet segmentation class for Sample Consensus methods and models that require the use of surface normals for estimation.

Definition at line 181 of file sac_segmentation.h.

Member Typedef Documentation

◆ PointCloud

typedef pcl::PointCloud<pcl::PointXYZ> pcl_ros::SACSegmentationFromNormals::PointCloud
private

Definition at line 183 of file sac_segmentation.h.

◆ PointCloudConstPtr

Definition at line 185 of file sac_segmentation.h.

◆ PointCloudN

Definition at line 187 of file sac_segmentation.h.

◆ PointCloudNConstPtr

Definition at line 189 of file sac_segmentation.h.

◆ PointCloudNPtr

Definition at line 188 of file sac_segmentation.h.

◆ PointCloudPtr

Definition at line 184 of file sac_segmentation.h.

Member Function Documentation

◆ axis_callback()

void pcl_ros::SACSegmentationFromNormals::axis_callback ( const pcl_msgs::ModelCoefficientsConstPtr &  model)
protected

Model callback.

Parameters
modelthe sample consensus model found

Definition at line 503 of file sac_segmentation.cpp.

◆ config_callback()

void pcl_ros::SACSegmentationFromNormals::config_callback ( SACSegmentationFromNormalsConfig &  config,
uint32_t  level 
)
protected

Dynamic reconfigure callback.

Parameters
configthe config object
levelthe dynamic reconfigure level

Definition at line 520 of file sac_segmentation.cpp.

◆ getInputTFframe()

std::string pcl_ros::SACSegmentationFromNormals::getInputTFframe ( )
inline

Get the TF frame the input PointCloud should be transformed into before processing.

Definition at line 198 of file sac_segmentation.h.

◆ getOutputTFframe()

std::string pcl_ros::SACSegmentationFromNormals::getOutputTFframe ( )
inline

Get the TF frame the PointCloud should be transformed into after processing.

Definition at line 206 of file sac_segmentation.h.

◆ input_callback()

void pcl_ros::SACSegmentationFromNormals::input_callback ( const PointCloudConstPtr cloud)
inlineprotected

Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp.

Definition at line 224 of file sac_segmentation.h.

◆ input_normals_indices_callback()

void pcl_ros::SACSegmentationFromNormals::input_normals_indices_callback ( const PointCloudConstPtr cloud,
const PointCloudNConstPtr cloud_normals,
const PointIndicesConstPtr indices 
)
protected

Input point cloud callback.

Parameters
cloudthe pointer to the input point cloud
cloud_normalsthe pointer to the input point cloud normals
indicesthe pointer to the input point cloud indices

DEBUG

Definition at line 586 of file sac_segmentation.cpp.

◆ onInit()

void pcl_ros::SACSegmentationFromNormals::onInit ( )
protectedvirtual

Nodelet initialization routine.

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 363 of file sac_segmentation.cpp.

◆ setInputTFframe()

void pcl_ros::SACSegmentationFromNormals::setInputTFframe ( std::string  tf_frame)
inline

Set the input TF frame the data should be transformed into before processing, if input.header.frame_id is different.

Parameters
tf_framethe TF frame the input PointCloud should be transformed into before processing

Definition at line 195 of file sac_segmentation.h.

◆ setOutputTFframe()

void pcl_ros::SACSegmentationFromNormals::setOutputTFframe ( std::string  tf_frame)
inline

Set the output TF frame the data should be transformed into after processing.

Parameters
tf_framethe TF frame the PointCloud should be transformed into after processing

Definition at line 203 of file sac_segmentation.h.

◆ subscribe()

void pcl_ros::SACSegmentationFromNormals::subscribe ( )
protectedvirtual

LazyNodelet connection routine.

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 446 of file sac_segmentation.cpp.

◆ unsubscribe()

void pcl_ros::SACSegmentationFromNormals::unsubscribe ( )
protectedvirtual

Reimplemented from pcl_ros::SACSegmentation.

Definition at line 490 of file sac_segmentation.cpp.

Member Data Documentation

◆ impl_

pcl::SACSegmentationFromNormals<pcl::PointXYZ, pcl::Normal> pcl_ros::SACSegmentationFromNormals::impl_
private

The PCL implementation used.

Definition at line 274 of file sac_segmentation.h.

◆ mutex_

boost::mutex pcl_ros::SACSegmentationFromNormals::mutex_
private

Internal mutex.

Definition at line 271 of file sac_segmentation.h.

◆ nf_

message_filters::PassThrough<PointIndices> pcl_ros::SACSegmentationFromNormals::nf_
protected

Null passthrough filter, used for pushing empty elements in the synchronizer.

Definition at line 233 of file sac_segmentation.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<SACSegmentationFromNormalsConfig> > pcl_ros::SACSegmentationFromNormals::srv_
protected

Pointer to a dynamic reconfigure service.

Definition at line 217 of file sac_segmentation.h.

◆ sub_axis_

ros::Subscriber pcl_ros::SACSegmentationFromNormals::sub_axis_
protected

The input PointCloud subscriber.

Definition at line 214 of file sac_segmentation.h.

◆ sub_normals_filter_

message_filters::Subscriber<PointCloudN> pcl_ros::SACSegmentationFromNormals::sub_normals_filter_
protected

The normals PointCloud subscriber filter.

Definition at line 211 of file sac_segmentation.h.

◆ sync_input_normals_indices_a_

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloudN, PointIndices> > > pcl_ros::SACSegmentationFromNormals::sync_input_normals_indices_a_
private

Synchronized input, normals, and indices.

Definition at line 277 of file sac_segmentation.h.

◆ sync_input_normals_indices_e_

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloudN, PointIndices> > > pcl_ros::SACSegmentationFromNormals::sync_input_normals_indices_e_
private

Definition at line 278 of file sac_segmentation.h.

◆ tf_input_frame_

std::string pcl_ros::SACSegmentationFromNormals::tf_input_frame_
protected

The input TF frame the data should be transformed into, if input.header.frame_id is different.

Definition at line 236 of file sac_segmentation.h.

◆ tf_input_orig_frame_

std::string pcl_ros::SACSegmentationFromNormals::tf_input_orig_frame_
protected

The original data input TF frame.

Definition at line 238 of file sac_segmentation.h.

◆ tf_output_frame_

std::string pcl_ros::SACSegmentationFromNormals::tf_output_frame_
protected

The output TF frame the data should be transformed into, if input.header.frame_id is different.

Definition at line 240 of file sac_segmentation.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Sat Feb 18 2023 03:54:54