38 #ifndef PCL_ROS_SAC_SEGMENTATION_H_ 39 #define PCL_ROS_SAC_SEGMENTATION_H_ 45 #include <pcl/segmentation/sac_segmentation.h> 48 #include <dynamic_reconfigure/server.h> 49 #include "pcl_ros/SACSegmentationConfig.h" 50 #include "pcl_ros/SACSegmentationFromNormalsConfig.h" 156 indices_.header =
fromPCL(input->header);
159 nf_pi_.
add (indices);
167 pcl::SACSegmentation<pcl::PointXYZ>
impl_;
174 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
227 indices.header.stamp =
fromPCL(cloud->header).stamp;
228 nf_.add (boost::make_shared<PointIndices> (indices));
252 void axis_callback (
const pcl_msgs::ModelCoefficientsConstPtr &model);
258 void config_callback (SACSegmentationFromNormalsConfig &config, uint32_t level);
265 void input_normals_indices_callback (
const PointCloudConstPtr &cloud,
266 const PointCloudNConstPtr &cloud_normals,
274 pcl::SACSegmentationFromNormals<pcl::PointXYZ, pcl::Normal>
impl_;
281 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
285 #endif //#ifndef PCL_ROS_SAC_SEGMENTATION_H_ ros::Publisher pub_model_
The output ModelCoefficients publisher.
pcl::PointCloud< pcl::PointXYZ > PointCloud
boost::mutex mutex_
Internal mutex.
PointCloud::ConstPtr PointCloudConstPtr
virtual void subscribe()
LazyNodelet connection routine.
void input_callback(const PointCloudConstPtr &input)
Input callback. Used when latched_indices_ is set.
void config_callback(SACSegmentationConfig &config, uint32_t level)
Dynamic reconfigure callback.
std::string tf_output_frame_
The output TF frame the data should be transformed into, if input.header.frame_id is different...
virtual void unsubscribe()
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointIndices > > > sync_input_indices_a_
std::string tf_input_orig_frame_
The original data input TF frame.
PointCloud::Ptr PointCloudPtr
void input_callback(const PointCloudConstPtr &cloud)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...
std::string tf_input_frame_
The input TF frame the data should be transformed into, if input.header.frame_id is different...
boost::mutex mutex_
Internal mutex.
void setOutputTFframe(std::string tf_frame)
Set the output TF frame the data should be transformed into after processing.
ros::Subscriber sub_input_
The input PointCloud subscriber.
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
ros::Subscriber sub_axis_
The input PointCloud subscriber.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointIndices > > > sync_input_indices_e_
Synchronized input, and indices.
PointIndices indices_
Pointer to a set of indices stored internally. (used when latched_indices_ is set).
PointCloud::ConstPtr PointCloudConstPtr
PCLNodelet represents the base PCL Nodelet class. All PCL nodelets should inherit from this class...
pcl_msgs::PointIndices PointIndices
message_filters::PassThrough< PointIndices > nf_
Null passthrough filter, used for pushing empty elements in the synchronizer.
void setOutputTFframe(std::string tf_frame)
Set the output TF frame the data should be transformed into after processing.
std::string getOutputTFframe()
Get the TF frame the PointCloud should be transformed into after processing.
SACSegmentationFromNormals represents the PCL nodelet segmentation class for Sample Consensus methods...
message_filters::PassThrough< pcl_msgs::PointIndices > nf_pi_
Null passthrough filter, used for pushing empty elements in the synchronizer.
pcl::SACSegmentationFromNormals< pcl::PointXYZ, pcl::Normal > impl_
The PCL implementation used.
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.
ros::Publisher pub_indices_
The output PointIndices publisher.
SACSegmentation represents the Nodelet segmentation class for Sample Consensus methods and models...
std::string tf_input_orig_frame_
The original data input TF frame.
void add(const MConstPtr &msg)
message_filters::Subscriber< PointCloudN > sub_normals_filter_
The normals PointCloud subscriber filter.
pcl::SACSegmentation< pcl::PointXYZ > impl_
The PCL implementation used.
PointCloudN::ConstPtr PointCloudNConstPtr
std::string getOutputTFframe()
Get the TF frame the PointCloud should be transformed into after processing.
std::string tf_output_frame_
The output TF frame the data should be transformed into, if input.header.frame_id is different...
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.
pcl::PointCloud< pcl::PointXYZ > PointCloud
void indices_callback(const PointIndicesConstPtr &indices)
Indices callback. Used when latched_indices_ is set.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointCloudN, PointIndices > > > sync_input_normals_indices_e_
virtual void onInit()
Nodelet initialization routine.
PointCloudN::Ptr PointCloudNPtr
PointCloud::Ptr PointCloudPtr
SACSegmentation()
Constructor.
pcl::PointCloud< pcl::Normal > PointCloudN
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointCloudN, PointIndices > > > sync_input_normals_indices_a_
Synchronized input, normals, and indices.
boost::shared_ptr< dynamic_reconfigure::Server< SACSegmentationFromNormalsConfig > > srv_
Pointer to a dynamic reconfigure service.
void input_indices_callback(const PointCloudConstPtr &cloud, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices is set.
std::string getInputTFframe()
Get the TF frame the input PointCloud should be transformed into before processing.
std::string tf_input_frame_
The input TF frame the data should be transformed into, if input.header.frame_id is different...
std::string getInputTFframe()
Get the TF frame the input PointCloud should be transformed into before processing.
PointIndices::ConstPtr PointIndicesConstPtr
boost::shared_ptr< dynamic_reconfigure::Server< SACSegmentationConfig > > srv_
Pointer to a dynamic reconfigure service.