#include <motion_detection.h>
Definition at line 28 of file motion_detection.h.
typedef std::vector<cv::KeyPoint> MotionDetection::KeyPoints |
Definition at line 34 of file motion_detection.h.
Definition at line 3 of file motion_detection.cpp.
Definition at line 27 of file motion_detection.cpp.
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.
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.
int MotionDetection::motion_detect_dilation_size_ [private] |
Definition at line 79 of file motion_detection.h.
double MotionDetection::motion_detect_downscale_factor_ [private] |
Definition at line 72 of file motion_detection.h.
int MotionDetection::motion_detect_flow_history_size_ [private] |
Definition at line 80 of file motion_detection.h.
bool MotionDetection::motion_detect_image_flow_filter_ [private] |
Definition at line 75 of file motion_detection.h.
double MotionDetection::motion_detect_inv_sensivity_ [private] |
Definition at line 73 of file motion_detection.h.
double MotionDetection::motion_detect_min_area_ [private] |
Definition at line 77 of file motion_detection.h.
double MotionDetection::motion_detect_min_blob_dist_ [private] |
Definition at line 78 of file motion_detection.h.
int MotionDetection::motion_detect_threshold_ [private] |
Definition at line 76 of file motion_detection.h.
bool MotionDetection::motion_detect_use_initial_flow_ [private] |
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.
ros::Timer MotionDetection::update_timer [private] |
Definition at line 52 of file motion_detection.h.