36 #ifndef JSK_PCL_ROS_UTILS_STATIC_POLYGON_ARRAY_PUBLISHER_H_ 37 #define JSK_PCL_ROS_UTILS_STATIC_POLYGON_ARRAY_PUBLISHER_H_ 41 #include <sensor_msgs/PointCloud2.h> 44 #include <jsk_recognition_msgs/PolygonArray.h> 45 #include <jsk_recognition_msgs/ModelCoefficientsArray.h> 55 #include <jsk_recognition_msgs/Int32Stamped.h> 56 #include <std_msgs/Header.h> 68 sensor_msgs::PointCloud2,
87 virtual void inputCallback(
const sensor_msgs::PointCloud2::ConstPtr& msg);
93 virtual void triggerCallback(
const sensor_msgs::PointCloud2::ConstPtr& input,
94 const jsk_recognition_msgs::Int32Stamped::ConstPtr& trigger);
jsk_recognition_msgs::ModelCoefficientsArray coefficients_
message_filters::sync_policies::ApproximateTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::Int32Stamped > SyncPolicy
std::vector< std::string > frame_ids_
virtual void timerCallback(const ros::TimerEvent &event)
virtual PCLModelCoefficientMsg polygonToModelCoefficients(const geometry_msgs::PolygonStamped &polygon)
ros::Publisher polygon_pub_
virtual bool readPolygonArray(const std::string ¶m)
virtual void triggerCallback(const sensor_msgs::PointCloud2::ConstPtr &input, const jsk_recognition_msgs::Int32Stamped::ConstPtr &trigger)
virtual void inputCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
virtual void unsubscribe()
virtual double getXMLDoubleValue(XmlRpc::XmlRpcValue val)
virtual void publishPolygon(const ros::Time &stamp)
ros::Timer periodic_timer_
ros::Publisher coefficients_pub_
jsk_recognition_msgs::PolygonArray polygons_
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_input_
message_filters::Subscriber< jsk_recognition_msgs::Int32Stamped > sub_trigger_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
pcl::ModelCoefficients PCLModelCoefficientMsg