38 #ifndef JSK_PCL_ROS_UTILS_CLOUD_ON_PLANE_H_ 39 #define JSK_PCL_ROS_UTILS_CLOUD_ON_PLANE_H_ 42 #include <jsk_recognition_msgs/PolygonArray.h> 49 #include <jsk_pcl_ros_utils/CloudOnPlaneConfig.h> 50 #include <dynamic_reconfigure/server.h> 51 #include <jsk_recognition_msgs/BoolStamped.h> 62 sensor_msgs::PointCloud2,
65 sensor_msgs::PointCloud2,
73 virtual void predicate(
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
74 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg);
virtual void unsubscribe()
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void predicate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg)
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PolygonArray > ApproximateSyncPolicy
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void configCallback(Config &config, uint32_t level)
virtual void publishPredicate(const std_msgs::Header &header, const bool v)
jsk_recognition_utils::SeriesedBoolean::Ptr buffer_
boost::shared_ptr< CloudOnPlane > Ptr
CloudOnPlaneConfig Config
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PolygonArray > SyncPolicy
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_