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>
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::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 |
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 |
SegmentDifferences obtains the difference between two spatially aligned point clouds and returns the difference between them for a maximum given distance threshold.
Definition at line 60 of file segment_differences.h.
|
private |
Definition at line 62 of file segment_differences.h.
|
private |
Definition at line 64 of file segment_differences.h.
|
private |
Definition at line 63 of file segment_differences.h.
|
inline |
Empty constructor.
Definition at line 68 of file segment_differences.h.
|
protected |
Dynamic reconfigure callback.
config | the config object |
level | the dynamic reconfigure level |
Definition at line 96 of file segment_differences.cpp.
|
protected |
Input point cloud callback.
cloud | the pointer to the input point cloud |
cloud_target | the pointcloud that we want to segment cloud from |
Definition at line 108 of file segment_differences.cpp.
|
protectedvirtual |
Nodelet initialization routine.
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 44 of file segment_differences.cpp.
|
protectedvirtual |
LazyNodelet connection routine.
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 61 of file segment_differences.cpp.
|
protectedvirtual |
Reimplemented from pcl_ros::PCLNodelet.
Definition at line 88 of file segment_differences.cpp.
|
private |
The PCL implementation used.
Definition at line 103 of file segment_differences.h.
|
protected |
Pointer to a dynamic reconfigure service.
Definition at line 79 of file segment_differences.h.
|
protected |
The message filter subscriber for PointCloud2.
Definition at line 68 of file segment_differences.h.
|
protected |
Definition at line 76 of file segment_differences.h.
|
protected |
Synchronized input, and planar hull.
Definition at line 75 of file segment_differences.h.