36 #ifndef JSK_PERCEPTION_FLOW_VELOCITY_THRESHOLDING_H_ 37 #define JSK_PERCEPTION_FLOW_VELOCITY_THRESHOLDING_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" 55 typedef jsk_perception::FlowVelocityThresholdingConfig
Config;
57 opencv_apps::FlowArrayStamped,
60 opencv_apps::FlowArrayStamped,
68 const opencv_apps::FlowArrayStamped::ConstPtr& flows_msg);
70 const opencv_apps::FlowArrayStamped::ConstPtr& flows_msg,
71 const sensor_msgs::CameraInfo::ConstPtr& info_msg);
73 const opencv_apps::FlowArrayStamped::ConstPtr& flows_msg,
74 const int image_height,
75 const int image_width);
96 #endif // JSK_PERCEPTION_FLOW_VELOCITY_THRESHOLDING_H_ boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::sync_policies::ExactTime< opencv_apps::FlowArrayStamped, sensor_msgs::CameraInfo > SyncPolicy
jsk_perception::FlowVelocityThresholdingConfig Config
message_filters::Subscriber< opencv_apps::FlowArrayStamped > sub_flow_
FlowVelocityThresholding()
virtual void configCallback(Config &config, uint32_t level)
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
message_filters::sync_policies::ApproximateTime< opencv_apps::FlowArrayStamped, sensor_msgs::CameraInfo > ApproximateSyncPolicy
virtual void callback(const opencv_apps::FlowArrayStamped::ConstPtr &flows_msg)
virtual void unsubscribe()
virtual void process(const opencv_apps::FlowArrayStamped::ConstPtr &flows_msg, const int image_height, const int image_width)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_