BoundaryEstimation estimates whether a set of points is lying on surface boundaries using an angle criterion. The code makes use of the estimated surface normals at each point in the input dataset. More...
#include <boundary.h>
Private Types | |
typedef pcl::PointCloud< pcl::Boundary > | PointCloudOut |
Private Member Functions | |
bool | childInit (ros::NodeHandle &nh) |
Child initialization routine. Internal method. More... | |
void | computePublish (const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &normals, const PointCloudInConstPtr &surface, const IndicesPtr &indices) |
Compute the feature and publish it. More... | |
void | emptyPublish (const PointCloudInConstPtr &cloud) |
Publish an empty point cloud of the feature output type. More... | |
Private Attributes | |
pcl::BoundaryEstimation< pcl::PointXYZ, pcl::Normal, pcl::Boundary > | impl_ |
Additional Inherited Members | |
Public Types inherited from pcl_ros::FeatureFromNormals | |
typedef sensor_msgs::PointCloud2 | PointCloud2 |
typedef pcl::PointCloud< pcl::Normal > | PointCloudN |
typedef PointCloudN::ConstPtr | PointCloudNConstPtr |
typedef PointCloudN::Ptr | PointCloudNPtr |
Public Types inherited from pcl_ros::Feature | |
typedef boost::shared_ptr< const std::vector< int > > | IndicesConstPtr |
typedef boost::shared_ptr< std::vector< int > > | IndicesPtr |
typedef pcl::KdTree< pcl::PointXYZ > | KdTree |
typedef pcl::KdTree< pcl::PointXYZ >::Ptr | KdTreePtr |
typedef pcl::PointCloud< pcl::PointXYZ > | PointCloudIn |
typedef PointCloudIn::ConstPtr | PointCloudInConstPtr |
typedef PointCloudIn::Ptr | PointCloudInPtr |
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::FeatureFromNormals | |
FeatureFromNormals () | |
Public Member Functions inherited from pcl_ros::Feature | |
Feature () | |
Empty constructor. 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 inherited from pcl_ros::Feature | |
void | config_callback (FeatureConfig &config, uint32_t level) |
Dynamic reconfigure callback. More... | |
void | input_callback (const PointCloudInConstPtr &input) |
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty elements with the same timestamp. More... | |
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::CallbackQueueInterface & | getMTCallbackQueue () const |
ros::NodeHandle & | getMTNodeHandle () const |
ros::NodeHandle & | getMTPrivateNodeHandle () const |
const V_string & | getMyArgv () const |
const std::string & | getName () const |
ros::NodeHandle & | getNodeHandle () const |
ros::NodeHandle & | getPrivateNodeHandle () const |
const M_string & | getRemappingArgs () const |
ros::CallbackQueueInterface & | getSTCallbackQueue () const |
std::string | getSuffixedName (const std::string &suffix) const |
Protected Attributes inherited from pcl_ros::FeatureFromNormals | |
PointCloudNConstPtr | normals_ |
A pointer to the input dataset that contains the point normals of the XYZ dataset. More... | |
Protected Attributes inherited from pcl_ros::Feature | |
int | k_ |
The number of K nearest neighbors to use for each point. More... | |
message_filters::PassThrough< PointCloudIn > | nf_pc_ |
message_filters::PassThrough< PointIndices > | nf_pi_ |
Null passthrough filter, used for pushing empty elements in the synchronizer. More... | |
double | search_radius_ |
The nearest neighbors search radius for each point. More... | |
int | spatial_locator_type_ |
Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Nearest Neigbor library) kd-tree 1: FLANN (Fast Library for Approximate Nearest Neighbors) kd-tree 2: Organized spatial dataset index. More... | |
boost::shared_ptr< dynamic_reconfigure::Server< FeatureConfig > > | srv_ |
Pointer to a dynamic reconfigure service. More... | |
ros::Subscriber | sub_input_ |
The input PointCloud subscriber. More... | |
message_filters::Subscriber< PointCloudIn > | sub_surface_filter_ |
The surface PointCloud subscriber filter. More... | |
KdTreePtr | tree_ |
The input point cloud dataset. More... | |
bool | use_surface_ |
Set to true if the nodelet needs to listen for incoming point clouds representing the search surface. 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< PointIndices > | sub_indices_filter_ |
The message filter subscriber for PointIndices. More... | |
message_filters::Subscriber< PointCloud > | sub_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::NodeHandle > | nh_ |
boost::shared_ptr< ros::NodeHandle > | pnh_ |
std::vector< ros::Publisher > | publishers_ |
ros::WallTimer | timer_ever_subscribed_ |
bool | verbose_connection_ |
BoundaryEstimation estimates whether a set of points is lying on surface boundaries using an angle criterion. The code makes use of the estimated surface normals at each point in the input dataset.
Definition at line 56 of file boundary.h.
|
private |
Definition at line 61 of file boundary.h.
|
inlineprivatevirtual |
Child initialization routine. Internal method.
Implements pcl_ros::FeatureFromNormals.
Definition at line 65 of file boundary.h.
|
privatevirtual |
Compute the feature and publish it.
Implements pcl_ros::FeatureFromNormals.
Definition at line 50 of file features/boundary.cpp.
|
privatevirtual |
Publish an empty point cloud of the feature output type.
Implements pcl_ros::FeatureFromNormals.
Definition at line 42 of file features/boundary.cpp.
|
private |
Definition at line 59 of file boundary.h.