Go to the documentation of this file.
38 #ifndef JSK_PCL_ROS_UTILS_CLOUD_ON_PLANE_H_
39 #define JSK_PCL_ROS_UTILS_CLOUD_ON_PLANE_H_
41 #include <jsk_topic_tools/diagnostic_nodelet.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>
56 class CloudOnPlane:
public jsk_topic_tools::DiagnosticNodelet
60 typedef CloudOnPlaneConfig
Config;
62 sensor_msgs::PointCloud2,
63 jsk_recognition_msgs::PolygonArray >
SyncPolicy;
65 sensor_msgs::PointCloud2,
74 virtual void predicate(
const sensor_msgs::PointCloud2::ConstPtr& cloud_msg,
75 const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg);
message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PolygonArray > SyncPolicy
CloudOnPlaneConfig Config
virtual void predicate(const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const jsk_recognition_msgs::PolygonArray::ConstPtr &polygon_msg)
virtual void publishPredicate(const std_msgs::Header &header, const bool v)
virtual void unsubscribe()
boost::shared_ptr< CloudOnPlane > Ptr
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygon_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
jsk_recognition_utils::SeriesedBoolean::Ptr buffer_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
virtual void configCallback(Config &config, uint32_t level)
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::PolygonArray > ApproximateSyncPolicy
jsk_pcl_ros_utils
Author(s): Yohei Kakiuchi
autogenerated on Fri May 16 2025 03:11:43