motion_detection.h
Go to the documentation of this file.
00001 #ifndef _HECTOR_MOTION_DETECTION_H_
00002 #define _HECTOR_MOTION_DETECTION_H_
00003 
00004 #include <ros/ros.h>
00005 #include <std_msgs/String.h>
00006 #include <opencv/cv.h>
00007 #include <cv_bridge/cv_bridge.h>
00008 
00009 #include <hector_worldmodel_msgs/ImagePercept.h>
00010 #include <image_transport/image_transport.h>
00011 #include <cv_bridge/cv_bridge.h>
00012 #include <opencv2/opencv.hpp>
00013 #include <opencv2/highgui/highgui.hpp>
00014 #include <sensor_msgs/image_encodings.h>
00015 
00016 #include <dynamic_reconfigure/server.h>
00017 #include <hector_motion_detection/MotionDetectionConfig.h>
00018 
00019 using hector_motion_detection::MotionDetectionConfig;
00020 
00021 class MotionDetection{
00022 public:
00023     MotionDetection();
00024     ~MotionDetection();
00025 private:
00026     void imageCallback(const sensor_msgs::ImageConstPtr& img); //, const sensor_msgs::CameraInfoConstPtr& info);
00027     //void mappingCallback(const thermaleye_msgs::Mapping& mapping);
00028     void dynRecParamCallback(MotionDetectionConfig &config, uint32_t level);
00029 
00030     ros::Publisher image_percept_pub_;
00031     image_transport::CameraSubscriber camera_sub_;
00032     image_transport::CameraPublisher image_motion_pub_;
00033     image_transport::CameraPublisher image_detected_pub_;
00034 
00035     image_transport::Subscriber image_sub_;
00036 
00037     dynamic_reconfigure::Server<MotionDetectionConfig> dyn_rec_server_;
00038 
00039     cv_bridge::CvImageConstPtr img_prev_ptr_;
00040     cv_bridge::CvImageConstPtr img_current_ptr_;
00041     cv_bridge::CvImageConstPtr img_current_col_ptr_;
00042 
00043     int motion_detect_threshold_;
00044     double min_percept_size, max_percept_size;
00045     double min_density;
00046     std::string percept_class_id_;
00047 
00048 };
00049 
00050 #endif


hector_motion_detection
Author(s): Alexander Stumpf
autogenerated on Mon Oct 6 2014 10:37:00