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

MovingLeastSquares represents a nodelet using the MovingLeastSquares implementation. The type of the output is the same as the input, it only smooths the XYZ coordinates according to the parameters. Normals are estimated at each point as well and published on a separate topic. More...

#include <moving_least_squares.h>

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

Protected Member Functions

void config_callback (MLSConfig &config, uint32_t level)
 Dynamic reconfigure callback. More...
 
virtual void onInit ()
 Nodelet initialization routine. More...
 
virtual void subscribe ()
 LazyNodelet connection routine. More...
 
virtual void unsubscribe ()
 
- Protected Member Functions inherited from pcl_ros::PCLNodelet
bool isValid (const ModelCoefficientsConstPtr &, const std::string &="model")
 Test whether a given ModelCoefficients message is "valid" (i.e., has values). More...
 
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 &, const std::string &="indices")
 Test whether a given PointIndices 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

double gaussian_parameter_
 How 'flat' should the neighbor weighting gaussian be (the smaller, the more local the fit). More...
 
int polynomial_order_
 The order of the polynomial to be fit. 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< MLSConfig > > srv_
 Pointer to a dynamic reconfigure service. More...
 
message_filters::Subscriber< PointCloudInsub_surface_filter_
 The surface PointCloud subscriber filter. More...
 
PointCloudInConstPtr surface_
 An input point cloud describing the surface that is to be used for nearest neighbors estimation. More...
 
KdTreePtr tree_
 A pointer to the spatial search object. More...
 
bool use_polynomial_fit_
 The number of K nearest neighbors to use for each point. 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::KdTree< PointInKdTree
 
typedef pcl::KdTree< PointIn >::Ptr KdTreePtr
 
typedef pcl::PointCloud< NormalOutNormalCloudOut
 
typedef pcl::PointNormal NormalOut
 
typedef pcl::PointCloud< PointInPointCloudIn
 
typedef boost::shared_ptr< const PointCloudInPointCloudInConstPtr
 
typedef boost::shared_ptr< PointCloudInPointCloudInPtr
 
typedef pcl::PointXYZ PointIn
 

Private Member Functions

void input_indices_callback (const PointCloudInConstPtr &cloud, const PointIndicesConstPtr &indices)
 Input point cloud callback. More...
 

Private Attributes

pcl::MovingLeastSquares< PointIn, NormalOutimpl_
 The PCL implementation used. More...
 
ros::Publisher pub_normals_
 The output PointCloud (containing the normals) publisher. More...
 
ros::Subscriber sub_input_
 The input PointCloud subscriber. More...
 
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloudIn, PointIndices > > > sync_input_indices_a_
 
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointIndices > > > sync_input_indices_e_
 Synchronized input, and indices. More...
 

Additional Inherited Members

- Public Types inherited from pcl_ros::PCLNodelet
typedef pcl::IndicesConstPtr IndicesConstPtr
 
typedef pcl::IndicesPtr 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 boost::shared_ptr< const PointCloudPointCloudConstPtr
 
typedef boost::shared_ptr< PointCloudPointCloudPtr
 
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

MovingLeastSquares represents a nodelet using the MovingLeastSquares implementation. The type of the output is the same as the input, it only smooths the XYZ coordinates according to the parameters. Normals are estimated at each point as well and published on a separate topic.

Author
Radu Bogdan Rusu, Zoltan-Csaba Marton

Definition at line 60 of file moving_least_squares.h.

Member Typedef Documentation

◆ KdTree

typedef pcl::KdTree<PointIn> pcl_ros::MovingLeastSquares::KdTree
private

Definition at line 70 of file moving_least_squares.h.

◆ KdTreePtr

typedef pcl::KdTree<PointIn>::Ptr pcl_ros::MovingLeastSquares::KdTreePtr
private

Definition at line 71 of file moving_least_squares.h.

◆ NormalCloudOut

Definition at line 68 of file moving_least_squares.h.

◆ NormalOut

typedef pcl::PointNormal pcl_ros::MovingLeastSquares::NormalOut
private

Definition at line 63 of file moving_least_squares.h.

◆ PointCloudIn

Definition at line 65 of file moving_least_squares.h.

◆ PointCloudInConstPtr

Definition at line 67 of file moving_least_squares.h.

◆ PointCloudInPtr

Definition at line 66 of file moving_least_squares.h.

◆ PointIn

typedef pcl::PointXYZ pcl_ros::MovingLeastSquares::PointIn
private

Definition at line 62 of file moving_least_squares.h.

Member Function Documentation

◆ config_callback()

void pcl_ros::MovingLeastSquares::config_callback ( MLSConfig &  config,
uint32_t  level 
)
protected

Dynamic reconfigure callback.

Parameters
configthe config object
levelthe dynamic reconfigure level

Definition at line 192 of file moving_least_squares.cpp.

◆ input_indices_callback()

void pcl_ros::MovingLeastSquares::input_indices_callback ( const PointCloudInConstPtr cloud,
const PointIndicesConstPtr indices 
)
private

Input point cloud callback.

Parameters
cloudthe pointer to the input point cloud
indicesthe pointer to the input point cloud indices

DEBUG

Definition at line 126 of file moving_least_squares.cpp.

◆ onInit()

void pcl_ros::MovingLeastSquares::onInit ( )
protectedvirtual

Nodelet initialization routine.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 42 of file moving_least_squares.cpp.

◆ subscribe()

void pcl_ros::MovingLeastSquares::subscribe ( )
protectedvirtual

LazyNodelet connection routine.

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 81 of file moving_least_squares.cpp.

◆ unsubscribe()

void pcl_ros::MovingLeastSquares::unsubscribe ( )
protectedvirtual

Reimplemented from pcl_ros::PCLNodelet.

Definition at line 113 of file moving_least_squares.cpp.

Member Data Documentation

◆ gaussian_parameter_

double pcl_ros::MovingLeastSquares::gaussian_parameter_
protected

How 'flat' should the neighbor weighting gaussian be (the smaller, the more local the fit).

Definition at line 93 of file moving_least_squares.h.

◆ impl_

pcl::MovingLeastSquares<PointIn, NormalOut> pcl_ros::MovingLeastSquares::impl_
private

The PCL implementation used.

Definition at line 133 of file moving_least_squares.h.

◆ polynomial_order_

int pcl_ros::MovingLeastSquares::polynomial_order_
protected

The order of the polynomial to be fit.

Definition at line 90 of file moving_least_squares.h.

◆ pub_normals_

ros::Publisher pcl_ros::MovingLeastSquares::pub_normals_
private

The output PointCloud (containing the normals) publisher.

Definition at line 139 of file moving_least_squares.h.

◆ search_radius_

double pcl_ros::MovingLeastSquares::search_radius_
protected

The nearest neighbors search radius for each point.

Definition at line 81 of file moving_least_squares.h.

◆ spatial_locator_type_

int pcl_ros::MovingLeastSquares::spatial_locator_type_
protected

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.

Definition at line 104 of file moving_least_squares.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<MLSConfig> > pcl_ros::MovingLeastSquares::srv_
protected

Pointer to a dynamic reconfigure service.

Definition at line 107 of file moving_least_squares.h.

◆ sub_input_

ros::Subscriber pcl_ros::MovingLeastSquares::sub_input_
private

The input PointCloud subscriber.

Definition at line 136 of file moving_least_squares.h.

◆ sub_surface_filter_

message_filters::Subscriber<PointCloudIn> pcl_ros::MovingLeastSquares::sub_surface_filter_
protected

The surface PointCloud subscriber filter.

Definition at line 97 of file moving_least_squares.h.

◆ surface_

PointCloudInConstPtr pcl_ros::MovingLeastSquares::surface_
protected

An input point cloud describing the surface that is to be used for nearest neighbors estimation.

Definition at line 75 of file moving_least_squares.h.

◆ sync_input_indices_a_

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloudIn, PointIndices> > > pcl_ros::MovingLeastSquares::sync_input_indices_a_
private

Definition at line 143 of file moving_least_squares.h.

◆ sync_input_indices_e_

boost::shared_ptr<message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn, PointIndices> > > pcl_ros::MovingLeastSquares::sync_input_indices_e_
private

Synchronized input, and indices.

Definition at line 142 of file moving_least_squares.h.

◆ tree_

KdTreePtr pcl_ros::MovingLeastSquares::tree_
protected

A pointer to the spatial search object.

Definition at line 78 of file moving_least_squares.h.

◆ use_polynomial_fit_

bool pcl_ros::MovingLeastSquares::use_polynomial_fit_
protected

The number of K nearest neighbors to use for each point.

Whether to use a polynomial fit.

Definition at line 87 of file moving_least_squares.h.


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


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Sat Feb 18 2023 03:54:54