54 NODELET_ERROR (
"[%s::onInit] Need a 'search_radius' parameter to be set before continuing!",
getName ().c_str ());
59 NODELET_ERROR (
"[%s::onInit] Need a 'spatial_locator' parameter to be set before continuing!",
getName ().c_str ());
64 srv_ = boost::make_shared<dynamic_reconfigure::Server<MLSConfig> > (*pnh_);
66 srv_->setCallback (f);
71 NODELET_DEBUG (
"[%s::onInit] Nodelet successfully created with the following parameters:\n" 72 " - use_indices : %s",
143 output.header = cloud->header;
148 if (indices && !
isValid (indices,
"indices"))
151 output.header = cloud->header;
159 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 160 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
165 NODELET_DEBUG (
"[%s::input_callback] PointCloud with %d data points, stamp %f, and frame %s on topic %s received.",
getName ().c_str (), cloud->width * cloud->height,
fromPCL(cloud->header).stamp.toSec (), cloud->header.frame_id.c_str (),
getMTPrivateNodeHandle ().
resolveName (
"input").c_str ());
173 indices_ptr.reset (
new std::vector<int> (indices->indices));
175 impl_.setIndices (indices_ptr);
184 output.header = cloud->header;
186 normals->header = cloud->header;
215 #if PCL_VERSION_COMPARE(<, 1, 9, 0) 220 NODELET_WARN (
"[config_callback] use_polynomial_fit is deprecated, use polynomial_order instead!");
221 if (
impl_.getPolynomialOrder () < 2)
223 impl_.setPolynomialOrder (2);
228 impl_.setPolynomialOrder (0);
ros::Subscriber sub_input_
The input PointCloud subscriber.
pcl::PointCloud< PointIn > PointCloudIn
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointIndices > > > sync_input_indices_e_
Synchronized input, and indices.
#define NODELET_ERROR(...)
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
#define NODELET_WARN(...)
int polynomial_order_
The order of the polynomial to be fit.
double gaussian_parameter_
How 'flat' should the neighbor weighting gaussian be (the smaller, the more local the fit)...
message_filters::Subscriber< PointIndices > sub_indices_filter_
The message filter subscriber for PointIndices.
void config_callback(MLSConfig &config, uint32_t level)
Dynamic reconfigure callback.
pcl::MovingLeastSquares< PointIn, NormalOut > impl_
The PCL implementation used.
void input_indices_callback(const PointCloudInConstPtr &cloud, const PointIndicesConstPtr &indices)
Input point cloud callback.
int spatial_locator_type_
Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Near...
pcl_ros::MovingLeastSquares MovingLeastSquares
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-ze...
virtual void subscribe()
LazyNodelet connection routine.
ros::NodeHandle & getMTPrivateNodeHandle() const
const std::string & getName() const
void publish(const boost::shared_ptr< M > &message) const
double search_radius_
The nearest neighbors search radius for each point.
bool use_polynomial_fit_
The number of K nearest neighbors to use for each point.
virtual void onInit()
Nodelet initialization routine.
std::string resolveName(const std::string &name, bool remap=true) const
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.
boost::shared_ptr< dynamic_reconfigure::Server< MLSConfig > > srv_
Pointer to a dynamic reconfigure service.
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloudIn, PointIndices > > > sync_input_indices_a_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
ros::Publisher pub_normals_
The output PointCloud (containing the normals) publisher.
bool approximate_sync_
True if we use an approximate time synchronizer versus an exact one (false by default).
pcl::IndicesPtr IndicesPtr
int max_queue_size_
The maximum queue size (default: 3).
ros::Publisher pub_output_
The output PointCloud publisher.
void fromPCL(const std::uint64_t &pcl_stamp, ros::Time &stamp)
uint32_t getNumSubscribers() const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
boost::shared_ptr< T > pcl_ptr(const boost::shared_ptr< T > &p)
virtual void unsubscribe()
#define NODELET_DEBUG(...)
bool use_indices_
Set to true if point indices are used.
PointIndices::ConstPtr PointIndicesConstPtr
boost::shared_ptr< T > ros_ptr(const boost::shared_ptr< T > &p)
pcl::PointCloud< NormalOut > NormalCloudOut
message_filters::Subscriber< PointCloud > sub_input_filter_
The message filter subscriber for PointCloud2.