37 #ifndef JSK_PCL_ROS_NORMAL_ESTIMATION_OMP_H_ 38 #define JSK_PCL_ROS_NORMAL_ESTIMATION_OMP_H_ 41 #include <sensor_msgs/PointCloud2.h> 42 #include <pcl_ros/FeatureConfig.h> 43 #include <dynamic_reconfigure/server.h> 46 #include <std_msgs/Float32.h> 54 typedef pcl_ros::FeatureConfig
Config;
63 const sensor_msgs::PointCloud2::ConstPtr& cloud_msg);
65 Config&
config, uint32_t level);
virtual void estimate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg)
virtual void unsubscribe()
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
std::string sensor_frame_
boost::shared_ptr< NormalEstimationOMP > Ptr
pcl_ros::FeatureConfig Config
virtual void configCallback(Config &config, uint32_t level)
ros::Publisher pub_with_xyz_
ros::Publisher pub_latest_time_
boost::mutex mutex
global mutex.
ros::Publisher pub_average_time_
jsk_recognition_utils::WallDurationTimer timer_