40 #ifndef VIDEO_TO_SCENE_H_
41 #define VIDEO_TO_SCENE_H_
43 #include <jsk_topic_tools/diagnostic_nodelet.h>
44 #include <dynamic_reconfigure/server.h>
45 #include <jsk_perception/VideoToSceneConfig.h>
46 #include <sensor_msgs/Image.h>
47 #include <opencv2/opencv.hpp>
48 #include <opencv2/bgsegm.hpp>
51 #include <std_msgs/Float64.h>
56 class VideoToScene:
public jsk_topic_tools::DiagnosticNodelet{
58 typedef VideoToSceneConfig
Config;
64 virtual void work(
const sensor_msgs::Image::ConstPtr& image_msg);
73 cv::Ptr<cv::bgsegm::BackgroundSubtractorGMG>
bgsubtractor;
81 #endif // VIDEO_TO_SCENE_H_