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

SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the difference between them for a maximum given distance threshold. More...

#include <segment_differences.h>

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

Public Member Functions

 SegmentDifferences ()
 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

void config_callback (SegmentDifferencesConfig &config, uint32_t level)
 Dynamic reconfigure callback. More...
 
void input_target_callback (const PointCloudConstPtr &cloud, const PointCloudConstPtr &cloud_target)
 Input point cloud callback. 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

boost::shared_ptr< dynamic_reconfigure::Server< SegmentDifferencesConfig > > srv_
 Pointer to a dynamic reconfigure service. More...
 
message_filters::Subscriber< PointCloudsub_target_filter_
 The message filter subscriber for PointCloud2. More...
 
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloud, PointCloud > > > sync_input_target_a_
 
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloud, PointCloud > > > sync_input_target_e_
 Synchronized input, and planar hull. 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::SegmentDifferences< 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
 

Detailed Description

SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the difference between them for a maximum given distance threshold.

Author
Radu Bogdan Rusu

Definition at line 60 of file segment_differences.h.

Member Typedef Documentation

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

Definition at line 62 of file segment_differences.h.

typedef PointCloud::ConstPtr pcl_ros::SegmentDifferences::PointCloudConstPtr
private

Definition at line 64 of file segment_differences.h.

typedef PointCloud::Ptr pcl_ros::SegmentDifferences::PointCloudPtr
private

Definition at line 63 of file segment_differences.h.

Constructor & Destructor Documentation

pcl_ros::SegmentDifferences::SegmentDifferences ( )
inline

Empty constructor.

Definition at line 68 of file segment_differences.h.

Member Function Documentation

void pcl_ros::SegmentDifferences::config_callback ( SegmentDifferencesConfig &  config,
uint32_t  level 
)
protected

Dynamic reconfigure callback.

Parameters
configthe config object
levelthe dynamic reconfigure level

Definition at line 96 of file segment_differences.cpp.

void pcl_ros::SegmentDifferences::input_target_callback ( const PointCloudConstPtr cloud,
const PointCloudConstPtr cloud_target 
)
protected

Input point cloud callback.

Parameters
cloudthe pointer to the input point cloud
cloud_targetthe pointcloud that we want to segment cloud from

Definition at line 108 of file segment_differences.cpp.

void pcl_ros::SegmentDifferences::onInit ( )
protectedvirtual

Nodelet initialization routine.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 44 of file segment_differences.cpp.

void pcl_ros::SegmentDifferences::subscribe ( )
protectedvirtual

LazyNodelet connection routine.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 61 of file segment_differences.cpp.

void pcl_ros::SegmentDifferences::unsubscribe ( )
protectedvirtual

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 88 of file segment_differences.cpp.

Member Data Documentation

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

The PCL implementation used.

Definition at line 103 of file segment_differences.h.

boost::shared_ptr<dynamic_reconfigure::Server<SegmentDifferencesConfig> > pcl_ros::SegmentDifferences::srv_
protected

Pointer to a dynamic reconfigure service.

Definition at line 79 of file segment_differences.h.

message_filters::Subscriber<PointCloud> pcl_ros::SegmentDifferences::sub_target_filter_
protected

The message filter subscriber for PointCloud2.

Definition at line 68 of file segment_differences.h.

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloud, PointCloud> > > pcl_ros::SegmentDifferences::sync_input_target_a_
protected

Definition at line 76 of file segment_differences.h.

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloud, PointCloud> > > pcl_ros::SegmentDifferences::sync_input_target_e_
protected

Synchronized input, and planar hull.

Definition at line 75 of file segment_differences.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Wed Jun 5 2019 19:52:53