19 #ifndef LK_OPTICAL_FLOW_LK_OPTICAL_FLOW_NODELET_H_
20 #define LK_OPTICAL_FLOW_LK_OPTICAL_FLOW_NODELET_H_
23 #include <nodelet/nodelet.h>
25 #include <ff_msgs/SetBool.h>
27 #include <image_transport/image_transport.h>
28 #include <ros/publisher.h>
29 #include <ros/subscriber.h>
41 void ReadParams(
void);
42 void ImageCallback(
const sensor_msgs::ImageConstPtr& msg);
43 bool EnableService(ff_msgs::SetBool::Request & req, ff_msgs::SetBool::Response & res);
45 boost::shared_ptr<LKOpticalFlow> inst_;
48 ros::Timer config_timer_;
52 image_transport::Publisher img_pub_;
53 image_transport::Subscriber img_sub_;
54 image_transport::CameraSubscriber cam_sub_;
56 ros::Publisher feature_pub_, reg_pub_;
57 ros::Subscriber filtered_feature_sub_;
58 ros::ServiceServer enable_srv_;
64 #endif // LK_OPTICAL_FLOW_LK_OPTICAL_FLOW_NODELET_H_