keypoints_publisher.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <ros/ros.h>
4 
5 #include <pcl/point_types.h>
6 #include <pcl_ros/pcl_nodelet.h>
7 #include <pcl/point_cloud.h>
9 
10 namespace jsk_pcl_ros
11 {
13  {
14  public:
15  virtual void onInit();
16  protected:
17  virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr& input);
18  virtual void extractKeypoints(pcl::PointCloud<pcl::PointXYZ>::Ptr cloud);
19  virtual void subscribe();
20  virtual void unsubscribe();
23  pcl::PointCloud<pcl::PointXYZ>::Ptr input_;
24  std_msgs::Header input_header_;
25  };
26 }
virtual void extractKeypoints(pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)
virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr &input)
pcl::PointCloud< pcl::PointXYZ >::Ptr input_
cloud


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47