50 #include <pcl/io/io.h> 71 NODELET_ERROR (
"[%s::onInit] Neither 'k_search' nor 'radius_search' set! Need to set at least one of these parameters before continuing.",
getName ().c_str ());
76 NODELET_ERROR (
"[%s::onInit] Need a 'spatial_locator' parameter to be set before continuing!",
getName ().c_str ());
84 srv_ = boost::make_shared<dynamic_reconfigure::Server<FeatureConfig> > (*pnh_);
86 srv_->setCallback (f);
142 NODELET_DEBUG (
"[%s::onInit] Nodelet successfully created with the following parameters:\n" 143 " - use_surface : %s\n" 145 " - radius_search : %f\n" 146 " - spatial_locator: %d",
155 if (
k_ != config.k_search)
157 k_ = config.k_search;
158 NODELET_DEBUG (
"[config_callback] Setting the number of K nearest neighbors to use for each point: %d.",
k_);
185 if (cloud_surface && !
isValid (cloud_surface,
"surface"))
187 NODELET_ERROR (
"[%s::input_surface_indices_callback] Invalid input surface!",
getName ().c_str ());
193 if (indices && !
isValid (indices))
195 NODELET_ERROR (
"[%s::input_surface_indices_callback] Invalid input indices!",
getName ().c_str ());
204 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 205 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 206 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
207 cloud->width * cloud->height,
pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (
"input").c_str (),
208 cloud_surface->width * cloud_surface->height,
pcl::getFieldsList (*cloud_surface).c_str (), cloud_surface->header.stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName (
"surface").c_str (),
209 indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName (
"indices").c_str ());
212 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 213 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
214 cloud->width * cloud->height,
pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (
"input").c_str (),
215 cloud_surface->width * cloud_surface->height,
pcl::getFieldsList (*cloud_surface).c_str (), cloud_surface->header.stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName (
"surface").c_str ());
220 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 221 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
222 cloud->width * cloud->height,
pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (
"input").c_str (),
223 indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName (
"indices").c_str ());
225 NODELET_DEBUG (
"[input_surface_indices_callback] PointCloud with %d data points, stamp %f, and frame %s on topic %s received.", cloud->width * cloud->height, cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (
"input").c_str ());
229 if ((
int)(cloud->width * cloud->height) <
k_)
231 NODELET_ERROR (
"[input_surface_indices_callback] Requested number of k-nearest neighbors (%d) is larger than the PointCloud size (%d)!",
k_, (
int)(cloud->width * cloud->height));
238 if (indices && !indices->header.frame_id.empty ())
239 vindices.reset (
new std::vector<int> (indices->indices));
263 if (!pnh_->getParam (
"k_search",
k_) && !pnh_->getParam (
"radius_search",
search_radius_))
265 NODELET_ERROR (
"[%s::onInit] Neither 'k_search' nor 'radius_search' set! Need to set at least one of these parameters before continuing.",
getName ().c_str ());
270 NODELET_ERROR (
"[%s::onInit] Need a 'spatial_locator' parameter to be set before continuing!",
getName ().c_str ());
277 sub_normals_filter_.subscribe (*pnh_,
"normals", max_queue_size_);
280 srv_ = boost::make_shared<dynamic_reconfigure::Server<FeatureConfig> > (*pnh_);
282 srv_->setCallback (f);
286 sync_input_normals_surface_indices_a_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ApproximateTime<PointCloudIn, PointCloudN, PointCloudIn, PointIndices> > > (
max_queue_size_);
288 sync_input_normals_surface_indices_e_ = boost::make_shared <message_filters::Synchronizer<sync_policies::ExactTime<PointCloudIn, PointCloudN, PointCloudIn, PointIndices> > > (
max_queue_size_);
345 NODELET_DEBUG (
"[%s::onInit] Nodelet successfully created with the following parameters:\n" 346 " - use_surface : %s\n" 348 " - radius_search : %f\n" 349 " - spatial_locator: %d",
367 NODELET_ERROR (
"[%s::input_normals_surface_indices_callback] Invalid input!",
getName ().c_str ());
373 if (cloud_surface && !
isValid (cloud_surface,
"surface"))
375 NODELET_ERROR (
"[%s::input_normals_surface_indices_callback] Invalid input surface!",
getName ().c_str ());
381 if (indices && !
isValid (indices))
383 NODELET_ERROR (
"[%s::input_normals_surface_indices_callback] Invalid input indices!",
getName ().c_str ());
391 NODELET_DEBUG (
"[%s::input_normals_surface_indices_callback]\n" 392 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 393 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 394 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 395 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
397 cloud->width * cloud->height,
pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (
"input").c_str (),
398 cloud_surface->width * cloud_surface->height,
pcl::getFieldsList (*cloud_surface).c_str (), cloud_surface->header.stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName (
"surface").c_str (),
399 cloud_normals->width * cloud_normals->height,
pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName (
"normals").c_str (),
400 indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName (
"indices").c_str ());
402 NODELET_DEBUG (
"[%s::input_normals_surface_indices_callback]\n" 403 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 404 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 405 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
407 cloud->width * cloud->height,
pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (
"input").c_str (),
408 cloud_surface->width * cloud_surface->height,
pcl::getFieldsList (*cloud_surface).c_str (), cloud_surface->header.stamp.toSec (), cloud_surface->header.frame_id.c_str (), pnh_->resolveName (
"surface").c_str (),
409 cloud_normals->width * cloud_normals->height,
pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName (
"normals").c_str ());
412 NODELET_DEBUG (
"[%s::input_normals_surface_indices_callback]\n" 413 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 414 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 415 " - PointIndices with %zu values, stamp %f, and frame %s on topic %s received.",
417 cloud->width * cloud->height,
pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (
"input").c_str (),
418 cloud_normals->width * cloud_normals->height,
pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName (
"normals").c_str (),
419 indices->indices.size (), indices->header.stamp.toSec (), indices->header.frame_id.c_str (), pnh_->resolveName (
"indices").c_str ());
421 NODELET_DEBUG (
"[%s::input_normals_surface_indices_callback]\n" 422 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.\n" 423 " - PointCloud with %d data points (%s), stamp %f, and frame %s on topic %s received.",
425 cloud->width * cloud->height,
pcl::getFieldsList (*cloud).c_str (), cloud->header.stamp.toSec (), cloud->header.frame_id.c_str (), pnh_->resolveName (
"input").c_str (),
426 cloud_normals->width * cloud_normals->height,
pcl::getFieldsList (*cloud_normals).c_str (), cloud_normals->header.stamp.toSec (), cloud_normals->header.frame_id.c_str (), pnh_->resolveName (
"normals").c_str ());
429 if ((
int)(cloud->width * cloud->height) <
k_)
431 NODELET_ERROR (
"[%s::input_normals_surface_indices_callback] Requested number of k-nearest neighbors (%d) is larger than the PointCloud size (%d)!",
getName ().c_str (),
k_, (
int)(cloud->width * cloud->height));
438 if (indices && !indices->header.frame_id.empty ())
439 vindices.reset (
new std::vector<int> (indices->indices));
virtual void emptyPublish(const PointCloudInConstPtr &cloud)=0
Publish an empty point cloud of the feature output type.
virtual void onInit()
Nodelet initialization routine.
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
#define NODELET_ERROR(...)
virtual void onInit()
Nodelet initialization routine. Reads in global parameters used by all nodelets.
virtual void onInit()
Nodelet initialization routine.
bool use_surface_
Set to true if the nodelet needs to listen for incoming point clouds representing the search surface...
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ApproximateTime< PointCloudIn, PointCloudIn, PointIndices > > > sync_input_surface_indices_a_
Synchronized input, surface, and point indices.
const std::string & getName() const
boost::shared_ptr< message_filters::Synchronizer< sync_policies::ExactTime< PointCloudIn, PointCloudIn, PointIndices > > > sync_input_surface_indices_e_
message_filters::Subscriber< PointIndices > sub_indices_filter_
The message filter subscriber for PointIndices.
void config_callback(FeatureConfig &config, uint32_t level)
Dynamic reconfigure callback.
message_filters::PassThrough< PointCloudIn > nf_pc_
void input_normals_surface_indices_callback(const PointCloudInConstPtr &cloud, const PointCloudNConstPtr &cloud_normals, const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices and use_surface are set.
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...
int k_
The number of K nearest neighbors to use for each point.
boost::shared_ptr< std::vector< int > > IndicesPtr
double search_radius_
The nearest neighbors search radius for each point.
boost::shared_ptr< dynamic_reconfigure::Server< FeatureConfig > > srv_
Pointer to a dynamic reconfigure service.
pcl::PointCloud< pcl::PointXYZ > PointCloudIn
void input_surface_indices_callback(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &cloud_surface, const PointIndicesConstPtr &indices)
Input point cloud callback. Used when use_indices and use_surface are set.
message_filters::PassThrough< PointIndices > nf_pi_
Null passthrough filter, used for pushing empty elements in the synchronizer.
message_filters::Subscriber< PointCloudIn > sub_surface_filter_
The surface PointCloud subscriber filter.
ros::Subscriber sub_input_
The input PointCloud subscriber.
uint32_t getNumSubscribers() const
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)
int spatial_locator_type_
Parameter for the spatial locator tree. By convention, the values represent: 0: ANN (Approximate Near...
bool approximate_sync_
True if we use an approximate time synchronizer versus an exact one (false by default).
int max_queue_size_
The maximum queue size (default: 3).
ros::Publisher pub_output_
The output PointCloud publisher.
PointCloudIn::ConstPtr PointCloudInConstPtr
virtual void computePublish(const PointCloudInConstPtr &cloud, const PointCloudInConstPtr &surface, const IndicesPtr &indices)=0
Compute the feature and publish it. Internal method.
#define NODELET_DEBUG(...)
bool use_indices_
Set to true if point indices are used.
PointIndices::ConstPtr PointIndicesConstPtr
virtual bool childInit(ros::NodeHandle &nh)=0
Child initialization routine. Internal method.
message_filters::Subscriber< PointCloud > sub_input_filter_
The message filter subscriber for PointCloud2.
void input_callback(const PointCloudInConstPtr &input)
Input point cloud callback. Because we want to use the same synchronizer object, we push back empty e...
Connection registerCallback(const C &callback)