Class SACSegmentation
Defined in File sac_segmentation.hpp
Inheritance Relationships
Base Type
public PCLNodelet
Derived Type
public pcl_ros::SACSegmentationFromNormals
(Class SACSegmentationFromNormals)
Class Documentation
-
class SACSegmentation : public PCLNodelet
SACSegmentation represents the Nodelet segmentation class for Sample Consensus methods and models, in the sense that it just creates a Nodelet wrapper for generic-purpose SAC-based segmentation.
- Author
Radu Bogdan Rusu
Subclassed by pcl_ros::SACSegmentationFromNormals
Public Functions
-
inline SACSegmentation()
Constructor.
-
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
-
virtual void onInit()
Nodelet initialization routine.
-
virtual void subscribe()
LazyNodelet connection routine.
-
virtual void unsubscribe()
-
void config_callback(SACSegmentationConfig &config, uint32_t level)
Dynamic reconfigure callback.
- Parameters:
config – the config object
level – the dynamic reconfigure level
-
void input_indices_callback(const PointCloudConstPtr &cloud, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices is set.
- Parameters:
cloud – the pointer to the input point cloud
indices – the pointer to the input point cloud indices
-
inline void indices_callback(const PointIndicesConstPtr &indices)
Indices callback. Used when latched_indices_ is set.
- Parameters:
indices – the pointer to the input point cloud indices
-
inline void input_callback(const PointCloudConstPtr &input)
Input callback. Used when latched_indices_ is set.
- Parameters:
input – the pointer to the input point cloud
Protected Attributes
-
int min_inliers_
-
ros::Publisher pub_indices_
The output PointIndices publisher.
-
ros::Publisher pub_model_
The output ModelCoefficients publisher.
-
ros::Subscriber sub_input_
The input PointCloud subscriber.
-
boost::shared_ptr<dynamic_reconfigure::Server<SACSegmentationConfig>> srv_
Pointer to a dynamic reconfigure service.
-
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.
-
message_filters::PassThrough<pcl_msgs::PointIndices> nf_pi_
Null passthrough filter, used for pushing empty elements in the synchronizer.
-
PointIndices indices_
Pointer to a set of indices stored internally. (used when latched_indices_ is set).