Class SACSegmentationFromNormals
Defined in File sac_segmentation.hpp
Inheritance Relationships
Base Type
public pcl_ros::SACSegmentation
(Class SACSegmentation)
Class Documentation
-
class SACSegmentationFromNormals : public pcl_ros::SACSegmentation
SACSegmentationFromNormals represents the PCL nodelet segmentation class for Sample Consensus methods and models that require the use of surface normals for estimation.
Public Functions
-
inline 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.
- Parameters:
tf_frame – the TF frame the input PointCloud should be transformed into before processing
-
inline std::string getInputTFframe()
Get the TF frame the input PointCloud should be transformed into before processing.
-
inline void setOutputTFframe(std::string tf_frame)
Set the output TF frame the data should be transformed into after processing.
- Parameters:
tf_frame – the TF frame the PointCloud should be transformed into after processing
-
inline std::string getOutputTFframe()
Get the TF frame the PointCloud should be transformed into after processing.
Protected Functions
-
inline 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.
-
virtual void onInit()
Nodelet initialization routine.
-
virtual void subscribe()
LazyNodelet connection routine.
-
virtual void unsubscribe()
-
void axis_callback(const pcl_msgs::ModelCoefficientsConstPtr &model)
Model callback.
- Parameters:
model – the sample consensus model found
-
void config_callback(SACSegmentationFromNormalsConfig &config, uint32_t level)
Dynamic reconfigure callback.
- Parameters:
config – the config object
level – the dynamic reconfigure level
-
void input_normals_indices_callback(const PointCloudConstPtr &cloud, const PointCloudNConstPtr &cloud_normals, const PointIndicesConstPtr &indices)
Input point cloud callback.
- Parameters:
cloud – the pointer to the input point cloud
cloud_normals – the pointer to the input point cloud normals
indices – the pointer to the input point cloud indices
Protected Attributes
-
message_filters::Subscriber<PointCloudN> sub_normals_filter_
The normals PointCloud subscriber filter.
-
ros::Subscriber sub_axis_
The input PointCloud subscriber.
-
boost::shared_ptr<dynamic_reconfigure::Server<SACSegmentationFromNormalsConfig>> srv_
Pointer to a dynamic reconfigure service.
-
message_filters::PassThrough<PointIndices> nf_
Null passthrough filter, used for pushing empty elements in the synchronizer.
-
std::string tf_input_frame_
The input TF frame the data should be transformed into, if input.header.frame_id is different.
-
std::string tf_input_orig_frame_
The original data input TF frame.
-
std::string tf_output_frame_
The output TF frame the data should be transformed into, if input.header.frame_id is different.
-
inline void setInputTFframe(std::string tf_frame)