36 #ifndef JSK_PERCEPTION_FLOW_VELOCITY_THRESHOLDING_H_
37 #define JSK_PERCEPTION_FLOW_VELOCITY_THRESHOLDING_H_
39 #include <jsk_topic_tools/diagnostic_nodelet.h>
44 #include <sensor_msgs/CameraInfo.h>
45 #include <opencv_apps/FlowArrayStamped.h>
46 #include <dynamic_reconfigure/server.h>
47 #include "jsk_perception/FlowVelocityThresholdingConfig.h"
51 class FlowVelocityThresholding:
public jsk_topic_tools::DiagnosticNodelet
56 typedef jsk_perception::FlowVelocityThresholdingConfig
Config;
58 opencv_apps::FlowArrayStamped,
61 opencv_apps::FlowArrayStamped,
69 const opencv_apps::FlowArrayStamped::ConstPtr& flows_msg);
71 const opencv_apps::FlowArrayStamped::ConstPtr& flows_msg,
72 const sensor_msgs::CameraInfo::ConstPtr& info_msg);
74 const opencv_apps::FlowArrayStamped::ConstPtr& flows_msg,
75 const int image_height,
76 const int image_width);
97 #endif // JSK_PERCEPTION_FLOW_VELOCITY_THRESHOLDING_H_