Public Member Functions | |
cv::Mat | affineRANSAC (AffineFlowMeasures &points, AffineFlowMeasures &inliers, float inlier_percent_est, float epsilon, int max_iterations=0, int min_iterations=2) |
AffineFlowMeasures | clusterAffineKMeans (cv::Mat &color_img, cv::Mat &u, cv::Mat &v, AffineFlowMeasures &points) |
AffineFlowMeasures | clusterFlowFields (cv::Mat &color_img, cv::Mat &depth_img, cv::Mat &u, cv::Mat &v, cv::Mat &mask) |
AffineFlowMeasures | clusterFlowFieldsKMeans (cv::Mat &color_img, cv::Mat &depth_img, cv::Mat &u, cv::Mat &v, cv::Mat &mask) |
AffineFlowMeasures | clusterFlowFieldsRANSAC (cv::Mat &color_img, cv::Mat &depth_img, cv::Mat &u, cv::Mat &v, cv::Mat &mask) |
AffineFlowMeasures | clusterSparseFlowKMeans (cv::Mat &color_img, cv::Mat &depth_img, cv::Mat &u, cv::Mat &v, cv::Mat &mask) |
AffineFlowMeasures | clusterSparseFlowRANSAC (cv::Mat &color_img, cv::Mat &depth_img, cv::Mat &u, cv::Mat &v, cv::Mat &mask) |
void | displayClusterCenters (AffineFlowMeasures &cluster_centers, AffineFlowMeasures &samples, cv::Mat &color_img, int cur_max_k=0) |
cv::Mat | estimateAffineTransform (cv::Mat &u, cv::Mat &v, const int r, const int c, const int radius) |
cv::Mat | estimateAffineTransform (AffineFlowMeasures &points) |
FlowClustering (FeatureTracker *ft, int kmeans_max_iter=200, double kmeans_epsilon=0.5, int kmeans_tries=5, int affine_estimate_radius=5, double surf_hessian=100) | |
AffineFlowMeasures | getAffineConsensus (AffineFlowMeasures points, cv::Mat cur_transform, float epsilon) |
float | getAffineDistortion (AffineFlowMeasure f, cv::Mat A) |
Public Attributes | |
int | affine_estimate_radius_ |
double | kmeans_epsilon_ |
int | kmeans_max_iter_ |
int | kmeans_tries_ |
int | max_k_ |
int | max_ransac_iters_ |
int | min_affine_point_set_size_ |
double | minimum_new_cluster_separation_ |
double | ransac_epsilon_ |
double | ransac_inlier_percent_est_ |
Protected Attributes | |
cv::Mat | dx_kernel_ |
cv::Mat | dy_kernel_ |
FeatureTracker * | ft_ |
cv::Mat | g_kernel_ |
Definition at line 1 of file flow_clustering.cpp.
FlowClustering::FlowClustering | ( | FeatureTracker * | ft, |
int | kmeans_max_iter = 200 , |
||
double | kmeans_epsilon = 0.5 , |
||
int | kmeans_tries = 5 , |
||
int | affine_estimate_radius = 5 , |
||
double | surf_hessian = 100 |
||
) | [inline] |
Definition at line 4 of file flow_clustering.cpp.
cv::Mat FlowClustering::affineRANSAC | ( | AffineFlowMeasures & | points, |
AffineFlowMeasures & | inliers, | ||
float | inlier_percent_est, | ||
float | epsilon, | ||
int | max_iterations = 0 , |
||
int | min_iterations = 2 |
||
) | [inline] |
Method fits an affine motion estimate to a set of image points using RANSAC
points | The set of individual flow estimates |
inliers | Returns the set of points determined to be inliers |
inlier_percent_est | the estimated percent of inliers in points |
epsilon | the threshold for being an inlier |
max_iterations | The maximum number of sample iterations to execute |
min_iterations | The minimum number of sample iterations to execute |
Definition at line 475 of file flow_clustering.cpp.
AffineFlowMeasures FlowClustering::clusterAffineKMeans | ( | cv::Mat & | color_img, |
cv::Mat & | u, | ||
cv::Mat & | v, | ||
AffineFlowMeasures & | points | ||
) | [inline] |
Definition at line 210 of file flow_clustering.cpp.
AffineFlowMeasures FlowClustering::clusterFlowFields | ( | cv::Mat & | color_img, |
cv::Mat & | depth_img, | ||
cv::Mat & | u, | ||
cv::Mat & | v, | ||
cv::Mat & | mask | ||
) | [inline] |
Definition at line 19 of file flow_clustering.cpp.
AffineFlowMeasures FlowClustering::clusterFlowFieldsKMeans | ( | cv::Mat & | color_img, |
cv::Mat & | depth_img, | ||
cv::Mat & | u, | ||
cv::Mat & | v, | ||
cv::Mat & | mask | ||
) | [inline] |
Definition at line 26 of file flow_clustering.cpp.
AffineFlowMeasures FlowClustering::clusterFlowFieldsRANSAC | ( | cv::Mat & | color_img, |
cv::Mat & | depth_img, | ||
cv::Mat & | u, | ||
cv::Mat & | v, | ||
cv::Mat & | mask | ||
) | [inline] |
Definition at line 64 of file flow_clustering.cpp.
AffineFlowMeasures FlowClustering::clusterSparseFlowKMeans | ( | cv::Mat & | color_img, |
cv::Mat & | depth_img, | ||
cv::Mat & | u, | ||
cv::Mat & | v, | ||
cv::Mat & | mask | ||
) | [inline] |
Definition at line 169 of file flow_clustering.cpp.
AffineFlowMeasures FlowClustering::clusterSparseFlowRANSAC | ( | cv::Mat & | color_img, |
cv::Mat & | depth_img, | ||
cv::Mat & | u, | ||
cv::Mat & | v, | ||
cv::Mat & | mask | ||
) | [inline] |
Definition at line 198 of file flow_clustering.cpp.
void FlowClustering::displayClusterCenters | ( | AffineFlowMeasures & | cluster_centers, |
AffineFlowMeasures & | samples, | ||
cv::Mat & | color_img, | ||
int | cur_max_k = 0 |
||
) | [inline] |
Display the results for the segmentation.
cluster_centers | The estimated segmentation centers |
samples | All points used in clustering |
color_img | The color image associated with the estimate |
Definition at line 536 of file flow_clustering.cpp.
cv::Mat FlowClustering::estimateAffineTransform | ( | cv::Mat & | u, |
cv::Mat & | v, | ||
const int | r, | ||
const int | c, | ||
const int | radius | ||
) | [inline] |
Definition at line 341 of file flow_clustering.cpp.
cv::Mat FlowClustering::estimateAffineTransform | ( | AffineFlowMeasures & | points | ) | [inline] |
Definition at line 387 of file flow_clustering.cpp.
AffineFlowMeasures FlowClustering::getAffineConsensus | ( | AffineFlowMeasures | points, |
cv::Mat | cur_transform, | ||
float | epsilon | ||
) | [inline] |
Determine the set of inliers for the current affine estimate
points | The set of all points given to RANSAC |
cur_transform | The current transform estimate |
epsilon | The threshold for acceptance as an inlier |
Definition at line 448 of file flow_clustering.cpp.
float FlowClustering::getAffineDistortion | ( | AffineFlowMeasure | f, |
cv::Mat | A | ||
) | [inline] |
See how closely the current affine estimate matches the estimated flow
f | The flow estimate |
A | The affine region estimate |
Definition at line 425 of file flow_clustering.cpp.
Definition at line 598 of file flow_clustering.cpp.
cv::Mat FlowClustering::dx_kernel_ [protected] |
Definition at line 587 of file flow_clustering.cpp.
cv::Mat FlowClustering::dy_kernel_ [protected] |
Definition at line 588 of file flow_clustering.cpp.
FeatureTracker* FlowClustering::ft_ [protected] |
Definition at line 590 of file flow_clustering.cpp.
cv::Mat FlowClustering::g_kernel_ [protected] |
Definition at line 589 of file flow_clustering.cpp.
Definition at line 593 of file flow_clustering.cpp.
Definition at line 592 of file flow_clustering.cpp.
Definition at line 596 of file flow_clustering.cpp.
Definition at line 597 of file flow_clustering.cpp.
Definition at line 600 of file flow_clustering.cpp.
Definition at line 599 of file flow_clustering.cpp.
Definition at line 601 of file flow_clustering.cpp.
Definition at line 594 of file flow_clustering.cpp.
Definition at line 595 of file flow_clustering.cpp.