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

ExtractPolygonalPrismData uses a set of point indices that represent a planar model, and together with a given height, generates a 3D polygonal prism. The polygonal prism is then used to segment all points lying inside it. More...

#include <extract_polygonal_prism_data.h>

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

Protected Member Functions

void config_callback (ExtractPolygonalPrismDataConfig &config, uint32_t level)
 Dynamic reconfigure callback. More...
 
void input_callback (const PointCloudConstPtr &input)
 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_hull_indices_callback (const PointCloudConstPtr &cloud, const PointCloudConstPtr &hull, const PointIndicesConstPtr &indices)
 Input point cloud callback. Used when use_indices is set. More...
 
void onInit ()
 Nodelet initialization routine. More...
 
void subscribe ()
 LazyNodelet connection routine. More...
 
void unsubscribe ()
 
- Protected Member Functions inherited from pcl_ros::PCLNodelet
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 &indices, const std::string &topic_name="indices")
 Test whether a given PointIndices message is "valid" (i.e., has values). More...
 
bool isValid (const ModelCoefficientsConstPtr &model, const std::string &topic_name="model")
 Test whether a given ModelCoefficients 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...
 
ros::Publisher pub_output_
 The output PointIndices publisher. More...
 
boost::shared_ptr< dynamic_reconfigure::Server< ExtractPolygonalPrismDataConfig > > srv_
 Pointer to a dynamic reconfigure service. More...
 
message_filters::Subscriber< PointCloudsub_hull_filter_
 The message filter subscriber for PointCloud2. More...
 
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointCloud, PointIndices > > > sync_input_hull_indices_a_
 
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointCloud, PointIndices > > > sync_input_hull_indices_e_
 Synchronized input, planar hull, and indices. 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 PointCloud::ConstPtr PointCloudConstPtr
 
typedef PointCloud::Ptr PointCloudPtr
 

Private Attributes

pcl::ExtractPolygonalPrismData< pcl::PointXYZ > impl_
 The PCL implementation used. More...
 

Additional Inherited Members

- Public Types inherited from pcl_ros::PCLNodelet
typedef boost::shared_ptr< const std::vector< int > > IndicesConstPtr
 
typedef boost::shared_ptr< std::vector< int > > 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 PointCloud::ConstPtr PointCloudConstPtr
 
typedef PointCloud::Ptr PointCloudPtr
 
typedef pcl_msgs::PointIndices PointIndices
 
typedef PointIndices::ConstPtr PointIndicesConstPtr
 
typedef PointIndices::Ptr PointIndicesPtr
 
- 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 ()
 

Detailed Description

ExtractPolygonalPrismData uses a set of point indices that represent a planar model, and together with a given height, generates a 3D polygonal prism. The polygonal prism is then used to segment all points lying inside it.

An example of its usage is to extract the data lying within a set of 3D boundaries (e.g., objects supported by a plane).

Author
Radu Bogdan Rusu

Definition at line 64 of file extract_polygonal_prism_data.h.

Member Typedef Documentation

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

Definition at line 66 of file extract_polygonal_prism_data.h.

typedef PointCloud::ConstPtr pcl_ros::ExtractPolygonalPrismData::PointCloudConstPtr
private

Definition at line 68 of file extract_polygonal_prism_data.h.

typedef PointCloud::Ptr pcl_ros::ExtractPolygonalPrismData::PointCloudPtr
private

Definition at line 67 of file extract_polygonal_prism_data.h.

Member Function Documentation

void pcl_ros::ExtractPolygonalPrismData::config_callback ( ExtractPolygonalPrismDataConfig &  config,
uint32_t  level 
)
protected

Dynamic reconfigure callback.

Parameters
configthe config object
levelthe dynamic reconfigure level

Definition at line 116 of file extract_polygonal_prism_data.cpp.

void pcl_ros::ExtractPolygonalPrismData::input_callback ( const PointCloudConstPtr input)
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 93 of file extract_polygonal_prism_data.h.

void pcl_ros::ExtractPolygonalPrismData::input_hull_indices_callback ( const PointCloudConstPtr cloud,
const PointCloudConstPtr hull,
const PointIndicesConstPtr indices 
)
protected

Input point cloud callback. Used when use_indices is set.

Parameters
cloudthe pointer to the input point cloud
hullthe pointer to the planar hull point cloud
indicesthe pointer to the input point cloud indices

DEBUG

Definition at line 136 of file extract_polygonal_prism_data.cpp.

void pcl_ros::ExtractPolygonalPrismData::onInit ( )
protectedvirtual

Nodelet initialization routine.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 50 of file extract_polygonal_prism_data.cpp.

void pcl_ros::ExtractPolygonalPrismData::subscribe ( )
protectedvirtual

LazyNodelet connection routine.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 68 of file extract_polygonal_prism_data.cpp.

void pcl_ros::ExtractPolygonalPrismData::unsubscribe ( )
protectedvirtual

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 105 of file extract_polygonal_prism_data.cpp.

Member Data Documentation

pcl::ExtractPolygonalPrismData<pcl::PointXYZ> pcl_ros::ExtractPolygonalPrismData::impl_
private

The PCL implementation used.

Definition at line 124 of file extract_polygonal_prism_data.h.

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

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

Definition at line 86 of file extract_polygonal_prism_data.h.

ros::Publisher pcl_ros::ExtractPolygonalPrismData::pub_output_
protected

The output PointIndices publisher.

Definition at line 72 of file extract_polygonal_prism_data.h.

boost::shared_ptr<dynamic_reconfigure::Server<ExtractPolygonalPrismDataConfig> > pcl_ros::ExtractPolygonalPrismData::srv_
protected

Pointer to a dynamic reconfigure service.

Definition at line 82 of file extract_polygonal_prism_data.h.

message_filters::Subscriber<PointCloud> pcl_ros::ExtractPolygonalPrismData::sub_hull_filter_
protected

The message filter subscriber for PointCloud2.

Definition at line 75 of file extract_polygonal_prism_data.h.

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud, PointIndices> > > pcl_ros::ExtractPolygonalPrismData::sync_input_hull_indices_a_
protected

Definition at line 79 of file extract_polygonal_prism_data.h.

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloud, PointIndices> > > pcl_ros::ExtractPolygonalPrismData::sync_input_hull_indices_e_
protected

Synchronized input, planar hull, and indices.

Definition at line 78 of file extract_polygonal_prism_data.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Mon Jun 10 2019 14:19:18