Public Types | Public Member Functions | Private Member Functions | Private Attributes
MotionDetection Class Reference

#include <motion_detection.h>

List of all members.

Public Types

typedef std::vector< cv::KeyPoint > KeyPoints

Public Member Functions

 MotionDetection ()
 ~MotionDetection ()

Private Member Functions

void colorizeDepth (const cv::Mat &gray, cv::Mat &rgb) const
void computeOpticalFlow (const cv::Mat &prev_img, const cv::Mat &cur_img, cv::Mat &optical_flow, bool use_initial_flow=false, bool filter=false) const
void computeOpticalFlowMagnitude (const cv::Mat &optical_flow, cv::Mat &optical_flow_mag) const
void detectBlobs (const cv::Mat &img, KeyPoints &keypoints) const
void drawBlobs (cv::Mat &img, const KeyPoints &keypoints, double scale=1.0) const
void drawOpticalFlowVectors (cv::Mat &img, const cv::Mat &optical_flow, int step=10, const cv::Scalar &color=CV_RGB(0, 255, 0)) const
void dynRecParamCallback (MotionDetectionConfig &config, uint32_t level)
void imageCallback (const sensor_msgs::ImageConstPtr &img)
void update (const ros::TimerEvent &event)

Private Attributes

image_transport::CameraSubscriber camera_sub_
dynamic_reconfigure::Server
< MotionDetectionConfig > 
dyn_rec_server_
std::list< cv::Mat > flow_history
image_transport::CameraPublisher image_detected_pub_
image_transport::CameraPublisher image_motion_pub_
ros::Publisher image_percept_pub_
image_transport::Subscriber image_sub_
cv_bridge::CvImageConstPtr img_prev_col_ptr_
cv_bridge::CvImageConstPtr img_prev_ptr_
sensor_msgs::ImageConstPtr last_img
int motion_detect_dilation_size_
double motion_detect_downscale_factor_
int motion_detect_flow_history_size_
bool motion_detect_image_flow_filter_
double motion_detect_inv_sensivity_
double motion_detect_min_area_
double motion_detect_min_blob_dist_
int motion_detect_threshold_
bool motion_detect_use_initial_flow_
cv::Mat optical_flow
std::string percept_class_id_
ros::Timer update_timer

Detailed Description

Definition at line 28 of file motion_detection.h.


Member Typedef Documentation

typedef std::vector<cv::KeyPoint> MotionDetection::KeyPoints

Definition at line 34 of file motion_detection.h.


Constructor & Destructor Documentation

Definition at line 3 of file motion_detection.cpp.

Definition at line 27 of file motion_detection.cpp.


Member Function Documentation

void MotionDetection::colorizeDepth ( const cv::Mat &  gray,
cv::Mat &  rgb 
) const [private]

Definition at line 31 of file motion_detection.cpp.

void MotionDetection::computeOpticalFlow ( const cv::Mat &  prev_img,
const cv::Mat &  cur_img,
cv::Mat &  optical_flow,
bool  use_initial_flow = false,
bool  filter = false 
) const [private]

Definition at line 93 of file motion_detection.cpp.

void MotionDetection::computeOpticalFlowMagnitude ( const cv::Mat &  optical_flow,
cv::Mat &  optical_flow_mag 
) const [private]

Definition at line 135 of file motion_detection.cpp.

void MotionDetection::detectBlobs ( const cv::Mat &  img,
KeyPoints keypoints 
) const [private]

Definition at line 171 of file motion_detection.cpp.

void MotionDetection::drawBlobs ( cv::Mat &  img,
const KeyPoints keypoints,
double  scale = 1.0 
) const [private]

Definition at line 150 of file motion_detection.cpp.

void MotionDetection::drawOpticalFlowVectors ( cv::Mat &  img,
const cv::Mat &  optical_flow,
int  step = 10,
const cv::Scalar &  color = CV_RGB(0, 255, 0) 
) const [private]

Definition at line 80 of file motion_detection.cpp.

void MotionDetection::dynRecParamCallback ( MotionDetectionConfig &  config,
uint32_t  level 
) [private]

Definition at line 313 of file motion_detection.cpp.

void MotionDetection::imageCallback ( const sensor_msgs::ImageConstPtr &  img) [private]

Definition at line 308 of file motion_detection.cpp.

void MotionDetection::update ( const ros::TimerEvent event) [private]

Definition at line 202 of file motion_detection.cpp.


Member Data Documentation

Definition at line 57 of file motion_detection.h.

dynamic_reconfigure::Server<MotionDetectionConfig> MotionDetection::dyn_rec_server_ [private]

Definition at line 61 of file motion_detection.h.

std::list<cv::Mat> MotionDetection::flow_history [private]

Definition at line 69 of file motion_detection.h.

Definition at line 59 of file motion_detection.h.

Definition at line 58 of file motion_detection.h.

Definition at line 56 of file motion_detection.h.

Definition at line 54 of file motion_detection.h.

Definition at line 66 of file motion_detection.h.

Definition at line 65 of file motion_detection.h.

sensor_msgs::ImageConstPtr MotionDetection::last_img [private]

Definition at line 63 of file motion_detection.h.

Definition at line 79 of file motion_detection.h.

Definition at line 72 of file motion_detection.h.

Definition at line 80 of file motion_detection.h.

Definition at line 75 of file motion_detection.h.

Definition at line 73 of file motion_detection.h.

Definition at line 77 of file motion_detection.h.

Definition at line 78 of file motion_detection.h.

Definition at line 76 of file motion_detection.h.

Definition at line 74 of file motion_detection.h.

cv::Mat MotionDetection::optical_flow [private]

Definition at line 68 of file motion_detection.h.

std::string MotionDetection::percept_class_id_ [private]

Definition at line 81 of file motion_detection.h.

Definition at line 52 of file motion_detection.h.


The documentation for this class was generated from the following files:


hector_motion_detection
Author(s): Alexander Stumpf
autogenerated on Mon Jan 18 2016 13:24:11