#include <optical_flow.h>
Public Member Functions | |
OpticalFlow () | |
void | process (cv::Mat &image) |
~OpticalFlow () | |
Private Member Functions | |
void | drawFeatures (cv::Mat &image, std::vector< cv::Point2f > const &old_corners, std::vector< cv::Point2f > const &new_corners) |
Draw the features onto the image, and draw lines between matches. | |
void | filterPoints (std::vector< cv::Point2f > &p1, std::vector< cv::Point2f > &p2, std::vector< unsigned char > const &status) |
Filter out all points from p1 and p2 who's corresponding status byte == 0. | |
void | trackFeatures (cv::Mat key_image, cv::Mat curr_image, std::vector< cv::Point2f > &corners, std::vector< cv::Point2f > &new_corners) |
Perform forward/backward LK tracking. | |
Private Attributes | |
std::vector< cv::Point2f > | key_corners_ |
cv::Mat | key_image_ |
double | matchscore_thresh_param_ |
int | num_keypoints_param_ |
Definition at line 21 of file optical_flow.h.
Definition at line 11 of file optical_flow.cpp.
Definition at line 16 of file optical_flow.cpp.
void OpticalFlow::drawFeatures | ( | cv::Mat & | image, |
std::vector< cv::Point2f > const & | old_corners, | ||
std::vector< cv::Point2f > const & | new_corners | ||
) | [private] |
Draw the features onto the image, and draw lines between matches.
Definition at line 67 of file optical_flow.cpp.
void OpticalFlow::filterPoints | ( | std::vector< cv::Point2f > & | p1, |
std::vector< cv::Point2f > & | p2, | ||
std::vector< unsigned char > const & | status | ||
) | [private] |
Filter out all points from p1 and p2 who's corresponding status byte == 0.
Definition at line 83 of file optical_flow.cpp.
void OpticalFlow::process | ( | cv::Mat & | image | ) |
Definition at line 20 of file optical_flow.cpp.
void OpticalFlow::trackFeatures | ( | cv::Mat | key_image, |
cv::Mat | curr_image, | ||
std::vector< cv::Point2f > & | corners, | ||
std::vector< cv::Point2f > & | new_corners | ||
) | [private] |
Perform forward/backward LK tracking.
key_image | The old keyframe image |
curr_image | The new incoming image |
corners | The old corners, found (e.g. by cv::goodFeaturesToTrack) in the key_image |
new_corners | A vector which will be filled with the locations of the corners in curr_image |
Definition at line 114 of file optical_flow.cpp.
std::vector<cv::Point2f> OpticalFlow::key_corners_ [private] |
Definition at line 33 of file optical_flow.h.
cv::Mat OpticalFlow::key_image_ [private] |
Definition at line 32 of file optical_flow.h.
double OpticalFlow::matchscore_thresh_param_ [private] |
Definition at line 36 of file optical_flow.h.
int OpticalFlow::num_keypoints_param_ [private] |
Definition at line 35 of file optical_flow.h.