Commit 40b238b0 authored by Tobias Senst's avatar Tobias Senst Committed by Alexander Alekhin

Merge pull request #2367 from tsenst:add_robust_interpolation_of_correspondence

Add RIC method for sparse match interpolation

* * add RIC

* sparse_match_interpolators EdgeAwareInterpolation - enhance limitation of the maximal number of matches to be interpolated from SHORT_MAX to INT_MAX by substituting short by int types

* * add RIC citation

* * update EdgeAwareInterpolatorImpl

* * add intermediate RIC implementation

* * implementation of new paralelization classes. First test where sucessfull.

* * update documentation RICInterpolatorImpl and RLOF

* * update CMakeLists.txt remove highgui
* add test for RIC
* add ASSERTION for curr image

* * add cost map interface

* * fix internal cost map allocation bug

* * remove white spaces
* fix warnings

* *fix compiler warnings

* * remove double whitespaces
* underscore from parameters
* substitute parallel_for_() classes with lambda functions
* remove complex assertion statements
* remove dead code
* substitute swap function with std::swap()
* ocv_define_module now contains video instead of tracking module

* * remove whitespace endings

* * documentation update

* * remove double declarations that lead to warnings

* * unrole tracker.py
*  remove double space
* use static for inner functions
* update create function
* modify mem init. to avoid manual memory management

* * uncomment parallel_for_ for parallelization

* * unrole unwanted changes
* uncomment paralellization

* * remove empty comment
* change CHECK to CHK_GD
* remove not necessary ;

* *documentation remove double space
parent cacec38e
Optical Flow Algorithms Optical Flow Algorithms
======================= =======================
Algorithms for running and evaluating deepflow, simpleflow, sparsetodenseflow and motion templates (silhouette flow). Algorithms for running and evaluating deepflow, simpleflow, sparsetodenseflow, robust local optical flow and motion templates (silhouette flow).
...@@ -104,9 +104,26 @@ ...@@ -104,9 +104,26 @@
number = {9}, number = {9},
} }
@phdthesis{Senst2019,
title={Estimation and analysis of motion in video data},
author={Senst, Tobias},
year={2019},
school={Technical Univerity Berlin},
doi = {10.14279/depositonce-9085},
url = {https://doi.org/10.14279/depositonce-9085}
}
@article{Tibshirani2008, @article{Tibshirani2008,
title={Fast computation of the median by successive binning}, title={Fast computation of the median by successive binning},
author={Tibshirani, Ryan J}, author={Tibshirani, Ryan J},
journal={arXiv preprint arXiv:0806.3301}, journal={arXiv preprint arXiv:0806.3301},
year={2008} year={2008}
} }
@inproceedings{Hu2017,
title={Robust interpolation of correspondences for large displacement optical flow},
author={Hu, Yinlin and Li, Yunsong and Song, Rui},
booktitle={IEEE Conference on Computer Vision and Pattern Recognition},
pages={481--489},
year={2017}
}
\ No newline at end of file
...@@ -30,14 +30,16 @@ enum SolverType { ...@@ -30,14 +30,16 @@ enum SolverType {
enum InterpolationType enum InterpolationType
{ {
INTERP_GEO = 0, /**< Fast geodesic interpolation, see @cite Geistert2016 */ INTERP_GEO = 0, /**< Fast geodesic interpolation, see @cite Geistert2016 */
INTERP_EPIC = 1, /**< Edge-preserving interpolation, see @cite Revaud2015,Geistert2016. */ INTERP_EPIC = 1, /**< Edge-preserving interpolation using ximgproc::EdgeAwareInterpolator, see @cite Revaud2015,Geistert2016. */
INTERP_RIC = 2, /**< SLIC based robust interpolation using ximgproc::RICInterpolator, see @cite Hu2017. */
}; };
/** @brief This is used store and set up the parameters of the robust local optical flow (RLOF) algoritm. /** @brief This is used store and set up the parameters of the robust local optical flow (RLOF) algoritm.
* *
* The RLOF is a fast local optical flow approach described in @cite Senst2012 @cite Senst2013 @cite Senst2014 * The RLOF is a fast local optical flow approach described in @cite Senst2012 @cite Senst2013 @cite Senst2014
* and @cite Senst2016 similar to the pyramidal iterative Lucas-Kanade method as * and @cite Senst2016 similar to the pyramidal iterative Lucas-Kanade method as
* proposed by @cite Bouguet00. The implementation is derived from optflow::calcOpticalFlowPyrLK(). * proposed by @cite Bouguet00. More details and experiments can be found in the following thesis @cite Senst2019.
* The implementation is derived from optflow::calcOpticalFlowPyrLK().
* This RLOF implementation can be seen as an improved pyramidal iterative Lucas-Kanade and includes * This RLOF implementation can be seen as an improved pyramidal iterative Lucas-Kanade and includes
* a set of improving modules. The main improvements in respect to the pyramidal iterative Lucas-Kanade * a set of improving modules. The main improvements in respect to the pyramidal iterative Lucas-Kanade
* are: * are:
...@@ -200,7 +202,8 @@ public: ...@@ -200,7 +202,8 @@ public:
* *
* The RLOF is a fast local optical flow approach described in @cite Senst2012 @cite Senst2013 @cite Senst2014 * The RLOF is a fast local optical flow approach described in @cite Senst2012 @cite Senst2013 @cite Senst2014
* and @cite Senst2016 similar to the pyramidal iterative Lucas-Kanade method as * and @cite Senst2016 similar to the pyramidal iterative Lucas-Kanade method as
* proposed by @cite Bouguet00. The implementation is derived from optflow::calcOpticalFlowPyrLK(). * proposed by @cite Bouguet00. More details and experiments can be found in the following thesis @cite Senst2019.
* The implementation is derived from optflow::calcOpticalFlowPyrLK().
* *
* The sparse-to-dense interpolation scheme allows for fast computation of dense optical flow using RLOF (see @cite Geistert2016). * The sparse-to-dense interpolation scheme allows for fast computation of dense optical flow using RLOF (see @cite Geistert2016).
* For this scheme the following steps are applied: * For this scheme the following steps are applied:
...@@ -324,6 +327,35 @@ public: ...@@ -324,6 +327,35 @@ public:
* @see ximgproc::fastGlobalSmootherFilter, setUsePostProc * @see ximgproc::fastGlobalSmootherFilter, setUsePostProc
*/ */
CV_WRAP virtual bool getUsePostProc() const = 0; CV_WRAP virtual bool getUsePostProc() const = 0;
//! @brief enables VariationalRefinement
/**
* @see getUseVariationalRefinement
*/
CV_WRAP virtual void setUseVariationalRefinement(bool val) = 0;
/** @copybrief setUseVariationalRefinement
* @see ximgproc::fastGlobalSmootherFilter, setUsePostProc
*/
CV_WRAP virtual bool getUseVariationalRefinement() const = 0;
//! @brief Parameter to tune the approximate size of the superpixel used for oversegmentation.
/**
* @see cv::ximgproc::createSuperpixelSLIC, cv::ximgproc::RICInterpolator
*/
CV_WRAP virtual void setRICSPSize(int val) = 0;
/** @copybrief setRICSPSize
* @see setRICSPSize
*/
CV_WRAP virtual int getRICSPSize() const = 0;
/** @brief Parameter to choose superpixel algorithm variant to use:
* - cv::ximgproc::SLICType SLIC segments image using a desired region_size (value: 100)
* - cv::ximgproc::SLICType SLICO will optimize using adaptive compactness factor (value: 101)
* - cv::ximgproc::SLICType MSLIC will optimize using manifold methods resulting in more content-sensitive superpixels (value: 102).
* @see cv::ximgproc::createSuperpixelSLIC, cv::ximgproc::RICInterpolator
*/
CV_WRAP virtual void setRICSLICType(int val) = 0;
/** @copybrief setRICSLICType
* @see setRICSLICType
*/
CV_WRAP virtual int getRICSLICType() const = 0;
//! @brief Creates instance of optflow::DenseRLOFOpticalFlow //! @brief Creates instance of optflow::DenseRLOFOpticalFlow
/** /**
* @param rlofParam see optflow::RLOFOpticalFlowParameter * @param rlofParam see optflow::RLOFOpticalFlowParameter
...@@ -333,9 +365,12 @@ public: ...@@ -333,9 +365,12 @@ public:
* @param epicK see setEPICK * @param epicK see setEPICK
* @param epicSigma see setEPICSigma * @param epicSigma see setEPICSigma
* @param epicLambda see setEPICLambda * @param epicLambda see setEPICLambda
* @param ricSPSize see setRICSPSize
* @param ricSLICType see setRICSLICType
* @param use_post_proc see setUsePostProc * @param use_post_proc see setUsePostProc
* @param fgsLambda see setFgsLambda * @param fgsLambda see setFgsLambda
* @param fgsSigma see setFgsSigma * @param fgsSigma see setFgsSigma
* @param use_variational_refinement see setUseVariationalRefinement
*/ */
CV_WRAP static Ptr<DenseRLOFOpticalFlow> create( CV_WRAP static Ptr<DenseRLOFOpticalFlow> create(
Ptr<RLOFOpticalFlowParameter> rlofParam = Ptr<RLOFOpticalFlowParameter>(), Ptr<RLOFOpticalFlowParameter> rlofParam = Ptr<RLOFOpticalFlowParameter>(),
...@@ -345,16 +380,20 @@ public: ...@@ -345,16 +380,20 @@ public:
int epicK = 128, int epicK = 128,
float epicSigma = 0.05f, float epicSigma = 0.05f,
float epicLambda = 999.0f, float epicLambda = 999.0f,
int ricSPSize = 15,
int ricSLICType = 100,
bool use_post_proc = true, bool use_post_proc = true,
float fgsLambda = 500.0f, float fgsLambda = 500.0f,
float fgsSigma = 1.5f); float fgsSigma = 1.5f,
bool use_variational_refinement = false);
}; };
/** @brief Class used for calculation sparse optical flow and feature tracking with robust local optical flow (RLOF) algorithms. /** @brief Class used for calculation sparse optical flow and feature tracking with robust local optical flow (RLOF) algorithms.
* *
* The RLOF is a fast local optical flow approach described in @cite Senst2012 @cite Senst2013 @cite Senst2014 * The RLOF is a fast local optical flow approach described in @cite Senst2012 @cite Senst2013 @cite Senst2014
* and @cite Senst2016 similar to the pyramidal iterative Lucas-Kanade method as * and @cite Senst2016 similar to the pyramidal iterative Lucas-Kanade method as
* proposed by @cite Bouguet00. The implementation is derived from optflow::calcOpticalFlowPyrLK(). * proposed by @cite Bouguet00. More details and experiments can be found in the following thesis @cite Senst2019.
* The implementation is derived from optflow::calcOpticalFlowPyrLK().
* *
* For the RLOF configuration see optflow::RLOFOpticalFlowParameter for further details. * For the RLOF configuration see optflow::RLOFOpticalFlowParameter for further details.
* Parameters have been described in @cite Senst2012, @cite Senst2013, @cite Senst2014 and @cite Senst2016. * Parameters have been described in @cite Senst2012, @cite Senst2013, @cite Senst2014 and @cite Senst2016.
...@@ -401,7 +440,8 @@ public: ...@@ -401,7 +440,8 @@ public:
* *
* The RLOF is a fast local optical flow approach described in @cite Senst2012 @cite Senst2013 @cite Senst2014 * The RLOF is a fast local optical flow approach described in @cite Senst2012 @cite Senst2013 @cite Senst2014
* and @cite Senst2016 similar to the pyramidal iterative Lucas-Kanade method as * and @cite Senst2016 similar to the pyramidal iterative Lucas-Kanade method as
* proposed by @cite Bouguet00. The implementation is derived from optflow::calcOpticalFlowPyrLK(). * proposed by @cite Bouguet00. More details and experiments can be found in the following thesis @cite Senst2019.
* The implementation is derived from optflow::calcOpticalFlowPyrLK().
* *
* The sparse-to-dense interpolation scheme allows for fast computation of dense optical flow using RLOF (see @cite Geistert2016). * The sparse-to-dense interpolation scheme allows for fast computation of dense optical flow using RLOF (see @cite Geistert2016).
* For this scheme the following steps are applied: * For this scheme the following steps are applied:
...@@ -430,12 +470,15 @@ public: ...@@ -430,12 +470,15 @@ public:
* supported: * supported:
* - **INTERP_GEO** applies the fast geodesic interpolation, see @cite Geistert2016. * - **INTERP_GEO** applies the fast geodesic interpolation, see @cite Geistert2016.
* - **INTERP_EPIC_RESIDUAL** applies the edge-preserving interpolation, see @cite Revaud2015,Geistert2016. * - **INTERP_EPIC_RESIDUAL** applies the edge-preserving interpolation, see @cite Revaud2015,Geistert2016.
* @param epicK see ximgproc::EdgeAwareInterpolator() sets the respective parameter. * @param epicK see ximgproc::EdgeAwareInterpolator sets the respective parameter.
* @param epicSigma see ximgproc::EdgeAwareInterpolator() sets the respective parameter. * @param epicSigma see ximgproc::EdgeAwareInterpolator sets the respective parameter.
* @param epicLambda see ximgproc::EdgeAwareInterpolator() sets the respective parameter. * @param epicLambda see ximgproc::EdgeAwareInterpolator sets the respective parameter.
* @param ricSPSize see ximgproc::RICInterpolator sets the respective parameter.
* @param ricSLICType see ximgproc::RICInterpolator sets the respective parameter.
* @param use_post_proc enables ximgproc::fastGlobalSmootherFilter() parameter. * @param use_post_proc enables ximgproc::fastGlobalSmootherFilter() parameter.
* @param fgsLambda sets the respective ximgproc::fastGlobalSmootherFilter() parameter. * @param fgsLambda sets the respective ximgproc::fastGlobalSmootherFilter() parameter.
* @param fgsSigma sets the respective ximgproc::fastGlobalSmootherFilter() parameter. * @param fgsSigma sets the respective ximgproc::fastGlobalSmootherFilter() parameter.
* @param use_variational_refinement enables VariationalRefinement
* *
* Parameters have been described in @cite Senst2012, @cite Senst2013, @cite Senst2014, @cite Senst2016. * Parameters have been described in @cite Senst2012, @cite Senst2013, @cite Senst2014, @cite Senst2016.
* For the RLOF configuration see optflow::RLOFOpticalFlowParameter for further details. * For the RLOF configuration see optflow::RLOFOpticalFlowParameter for further details.
...@@ -451,14 +494,17 @@ CV_EXPORTS_W void calcOpticalFlowDenseRLOF(InputArray I0, InputArray I1, InputOu ...@@ -451,14 +494,17 @@ CV_EXPORTS_W void calcOpticalFlowDenseRLOF(InputArray I0, InputArray I1, InputOu
float forwardBackwardThreshold = 0, Size gridStep = Size(6, 6), float forwardBackwardThreshold = 0, Size gridStep = Size(6, 6),
InterpolationType interp_type = InterpolationType::INTERP_EPIC, InterpolationType interp_type = InterpolationType::INTERP_EPIC,
int epicK = 128, float epicSigma = 0.05f, float epicLambda = 100.f, int epicK = 128, float epicSigma = 0.05f, float epicLambda = 100.f,
bool use_post_proc = true, float fgsLambda = 500.0f, float fgsSigma = 1.5f); int ricSPSize = 15, int ricSLICType = 100,
bool use_post_proc = true, float fgsLambda = 500.0f, float fgsSigma = 1.5f,
bool use_variational_refinement = false);
/** @brief Calculates fast optical flow for a sparse feature set using the robust local optical flow (RLOF) similar /** @brief Calculates fast optical flow for a sparse feature set using the robust local optical flow (RLOF) similar
* to optflow::calcOpticalFlowPyrLK(). * to optflow::calcOpticalFlowPyrLK().
* *
* The RLOF is a fast local optical flow approach described in @cite Senst2012 @cite Senst2013 @cite Senst2014 * The RLOF is a fast local optical flow approach described in @cite Senst2012 @cite Senst2013 @cite Senst2014
* and @cite Senst2016 similar to the pyramidal iterative Lucas-Kanade method as * and @cite Senst2016 similar to the pyramidal iterative Lucas-Kanade method as
* proposed by @cite Bouguet00. The implementation is derived from optflow::calcOpticalFlowPyrLK(). * proposed by @cite Bouguet00. More details and experiments can be found in the following thesis @cite Senst2019.
* The implementation is derived from optflow::calcOpticalFlowPyrLK().
* *
* @param prevImg first 8-bit input image. If The cross-based RLOF is used (by selecting optflow::RLOFOpticalFlowParameter::supportRegionType * @param prevImg first 8-bit input image. If The cross-based RLOF is used (by selecting optflow::RLOFOpticalFlowParameter::supportRegionType
* = SupportRegionType::SR_CROSS) image has to be a 8-bit 3 channel image. * = SupportRegionType::SR_CROSS) image has to be a 8-bit 3 channel image.
......
...@@ -12,7 +12,7 @@ using namespace optflow; ...@@ -12,7 +12,7 @@ using namespace optflow;
const String keys = "{help h usage ? | | print this message }" const String keys = "{help h usage ? | | print this message }"
"{@image1 | | image1 }" "{@image1 | | image1 }"
"{@image2 | | image2 }" "{@image2 | | image2 }"
"{@algorithm | | [farneback, simpleflow, tvl1, deepflow, sparsetodenseflow, pcaflow, DISflow_ultrafast, DISflow_fast, DISflow_medium] }" "{@algorithm | | [farneback, simpleflow, tvl1, deepflow, sparsetodenseflow, RLOF_EPIC, RLOF_RIC, pcaflow, DISflow_ultrafast, DISflow_fast, DISflow_medium] }"
"{@groundtruth | | path to the .flo file (optional), Middlebury format }" "{@groundtruth | | path to the .flo file (optional), Middlebury format }"
"{m measure |endpoint| error measure - [endpoint or angular] }" "{m measure |endpoint| error measure - [endpoint or angular] }"
"{r region |all | region to compute stats about [all, discontinuities, untextured] }" "{r region |all | region to compute stats about [all, discontinuities, untextured] }"
...@@ -259,6 +259,20 @@ int main( int argc, char** argv ) ...@@ -259,6 +259,20 @@ int main( int argc, char** argv )
algorithm = createOptFlow_DeepFlow(); algorithm = createOptFlow_DeepFlow();
else if ( method == "sparsetodenseflow" ) else if ( method == "sparsetodenseflow" )
algorithm = createOptFlow_SparseToDense(); algorithm = createOptFlow_SparseToDense();
else if (method == "RLOF_EPIC")
{
algorithm = createOptFlow_DenseRLOF();
Ptr<DenseRLOFOpticalFlow> rlof = algorithm.dynamicCast< DenseRLOFOpticalFlow>();
rlof->setInterpolation(INTERP_EPIC);
rlof->setForwardBackward(1.f);
}
else if (method == "RLOF_RIC")
{
algorithm = createOptFlow_DenseRLOF();
Ptr<DenseRLOFOpticalFlow> rlof = algorithm.dynamicCast< DenseRLOFOpticalFlow>();;
rlof->setInterpolation(INTERP_RIC);
rlof->setForwardBackward(1.f);
}
else if ( method == "pcaflow" ) { else if ( method == "pcaflow" ) {
if ( parser.has("prior") ) { if ( parser.has("prior") ) {
String prior = parser.get<String>("prior"); String prior = parser.get<String>("prior");
......
...@@ -70,6 +70,9 @@ public: ...@@ -70,6 +70,9 @@ public:
, fgs_lambda(500.0f) , fgs_lambda(500.0f)
, fgs_sigma(1.5f) , fgs_sigma(1.5f)
, use_post_proc(true) , use_post_proc(true)
, use_variational_refinement(false)
, sp_size(15)
, slic_type(ximgproc::SLIC)
{ {
prevPyramid[0] = cv::Ptr<CImageBuffer>(new CImageBuffer); prevPyramid[0] = cv::Ptr<CImageBuffer>(new CImageBuffer);
...@@ -107,6 +110,15 @@ public: ...@@ -107,6 +110,15 @@ public:
virtual bool getUsePostProc() const CV_OVERRIDE { return use_post_proc; } virtual bool getUsePostProc() const CV_OVERRIDE { return use_post_proc; }
virtual void setUsePostProc(bool val) CV_OVERRIDE { use_post_proc = val; } virtual void setUsePostProc(bool val) CV_OVERRIDE { use_post_proc = val; }
virtual void setUseVariationalRefinement(bool val) CV_OVERRIDE { use_variational_refinement = val; }
virtual bool getUseVariationalRefinement() const CV_OVERRIDE { return use_variational_refinement; }
virtual void setRICSPSize(int val) CV_OVERRIDE { sp_size = val; }
virtual int getRICSPSize() const CV_OVERRIDE { return sp_size; }
virtual void setRICSLICType(int val) CV_OVERRIDE { slic_type = static_cast<ximgproc::SLICType>(val); }
virtual int getRICSLICType() const CV_OVERRIDE { return slic_type; }
virtual void calc(InputArray I0, InputArray I1, InputOutputArray flow) CV_OVERRIDE virtual void calc(InputArray I0, InputArray I1, InputOutputArray flow) CV_OVERRIDE
{ {
CV_Assert(!I0.empty() && I0.depth() == CV_8U && (I0.channels() == 3 || I0.channels() == 1)); CV_Assert(!I0.empty() && I0.depth() == CV_8U && (I0.channels() == 3 || I0.channels() == 1));
...@@ -116,7 +128,7 @@ public: ...@@ -116,7 +128,7 @@ public:
param = Ptr<RLOFOpticalFlowParameter>(new RLOFOpticalFlowParameter()); param = Ptr<RLOFOpticalFlowParameter>(new RLOFOpticalFlowParameter());
if (param->supportRegionType == SR_CROSS) if (param->supportRegionType == SR_CROSS)
CV_Assert( I0.channels() == 3 && I1.channels() == 3); CV_Assert( I0.channels() == 3 && I1.channels() == 3);
CV_Assert(interp_type == InterpolationType::INTERP_EPIC || interp_type == InterpolationType::INTERP_GEO); CV_Assert(interp_type == InterpolationType::INTERP_EPIC || interp_type == InterpolationType::INTERP_GEO || interp_type == InterpolationType::INTERP_RIC);
// if no parameter is used use the default parameter // if no parameter is used use the default parameter
Mat prevImage = I0.getMat(); Mat prevImage = I0.getMat();
...@@ -184,9 +196,23 @@ public: ...@@ -184,9 +196,23 @@ public:
gd->setK(k); gd->setK(k);
gd->setSigma(sigma); gd->setSigma(sigma);
gd->setLambda(lambda); gd->setLambda(lambda);
gd->setFGSLambda(fgs_lambda);
gd->setFGSSigma(fgs_sigma);
gd->setUsePostProcessing(false); gd->setUsePostProcessing(false);
gd->interpolate(prevImage, filtered_prevPoints, currImage, filtered_currPoints, dense_flow); gd->interpolate(prevImage, filtered_prevPoints, currImage, filtered_currPoints, dense_flow);
} }
else if (interp_type == InterpolationType::INTERP_RIC)
{
Ptr<ximgproc::RICInterpolator> gd = ximgproc::createRICInterpolator();
gd->setK(k);
gd->setFGSLambda(fgs_lambda);
gd->setFGSSigma(fgs_sigma);
gd->setSuperpixelSize(sp_size);
gd->setSuperpixelMode(slic_type);
gd->setUseGlobalSmootherFilter(false);
gd->setUseVariationalRefinement(false);
gd->interpolate(prevImage, filtered_prevPoints, currImage, filtered_currPoints, dense_flow);
}
else else
{ {
Mat blurredPrevImage, blurredCurrImage; Mat blurredPrevImage, blurredCurrImage;
...@@ -200,6 +226,15 @@ public: ...@@ -200,6 +226,15 @@ public:
cv::bilateralFilter(vecMats[1], vecMats2[1], 5, 2, 20); cv::bilateralFilter(vecMats[1], vecMats2[1], 5, 2, 20);
cv::merge(vecMats2, dense_flow); cv::merge(vecMats2, dense_flow);
} }
if (use_variational_refinement)
{
Mat prevGrey, currGrey;
Ptr<VariationalRefinement > variationalrefine = VariationalRefinement::create();
cvtColor(prevImage, prevGrey, COLOR_BGR2GRAY);
cvtColor(currImage, currGrey, COLOR_BGR2GRAY);
variationalrefine->setOmega(1.9f);
variationalrefine->calc(prevGrey, currGrey, flow);
}
if (use_post_proc) if (use_post_proc)
{ {
ximgproc::fastGlobalSmootherFilter(prevImage, flow, flow, fgs_lambda, fgs_sigma); ximgproc::fastGlobalSmootherFilter(prevImage, flow, flow, fgs_lambda, fgs_sigma);
...@@ -227,6 +262,9 @@ protected: ...@@ -227,6 +262,9 @@ protected:
float fgs_lambda; float fgs_lambda;
float fgs_sigma; float fgs_sigma;
bool use_post_proc; bool use_post_proc;
bool use_variational_refinement;
int sp_size;
ximgproc::SLICType slic_type;
}; };
Ptr<DenseRLOFOpticalFlow> DenseRLOFOpticalFlow::create( Ptr<DenseRLOFOpticalFlow> DenseRLOFOpticalFlow::create(
...@@ -237,9 +275,12 @@ Ptr<DenseRLOFOpticalFlow> DenseRLOFOpticalFlow::create( ...@@ -237,9 +275,12 @@ Ptr<DenseRLOFOpticalFlow> DenseRLOFOpticalFlow::create(
int epicK, int epicK,
float epicSigma, float epicSigma,
float epicLambda, float epicLambda,
int ricSPSize,
int ricSLICType,
bool use_post_proc, bool use_post_proc,
float fgs_lambda, float fgs_lambda,
float fgs_sigma) float fgs_sigma,
bool use_variational_refinement)
{ {
Ptr<DenseRLOFOpticalFlow> algo = makePtr<DenseOpticalFlowRLOFImpl>(); Ptr<DenseRLOFOpticalFlow> algo = makePtr<DenseOpticalFlowRLOFImpl>();
algo->setRLOFOpticalFlowParameter(rlofParam); algo->setRLOFOpticalFlowParameter(rlofParam);
...@@ -252,6 +293,9 @@ Ptr<DenseRLOFOpticalFlow> DenseRLOFOpticalFlow::create( ...@@ -252,6 +293,9 @@ Ptr<DenseRLOFOpticalFlow> DenseRLOFOpticalFlow::create(
algo->setUsePostProc(use_post_proc); algo->setUsePostProc(use_post_proc);
algo->setFgsLambda(fgs_lambda); algo->setFgsLambda(fgs_lambda);
algo->setFgsSigma(fgs_sigma); algo->setFgsSigma(fgs_sigma);
algo->setRICSLICType(ricSLICType);
algo->setRICSPSize(ricSPSize);
algo->setUseVariationalRefinement(use_variational_refinement);
return algo; return algo;
} }
...@@ -381,11 +425,13 @@ void calcOpticalFlowDenseRLOF(InputArray I0, InputArray I1, InputOutputArray flo ...@@ -381,11 +425,13 @@ void calcOpticalFlowDenseRLOF(InputArray I0, InputArray I1, InputOutputArray flo
float forewardBackwardThreshold, Size gridStep, float forewardBackwardThreshold, Size gridStep,
InterpolationType interp_type, InterpolationType interp_type,
int epicK, float epicSigma, float epicLambda, int epicK, float epicSigma, float epicLambda,
bool use_post_proc, float fgsLambda, float fgsSigma) int superpixelSize, int superpixelType,
bool use_post_proc, float fgsLambda, float fgsSigma, bool use_variational_refinement)
{ {
Ptr<DenseRLOFOpticalFlow> algo = DenseRLOFOpticalFlow::create( Ptr<DenseRLOFOpticalFlow> algo = DenseRLOFOpticalFlow::create(
rlofParam, forewardBackwardThreshold, gridStep, interp_type, rlofParam, forewardBackwardThreshold, gridStep, interp_type,
epicK, epicSigma, epicLambda, use_post_proc, fgsLambda, fgsSigma); epicK, epicSigma, epicLambda, superpixelSize, superpixelType,
use_post_proc, fgsLambda, fgsSigma, use_variational_refinement);
algo->calc(I0, I1, flow); algo->calc(I0, I1, flow);
algo->collectGarbage(); algo->collectGarbage();
} }
......
set(the_description "Extended image processing module. It includes edge-aware filters and etc.") set(the_description "Extended image processing module. It includes edge-aware filters and etc.")
ocv_define_module(ximgproc opencv_core opencv_imgproc opencv_calib3d opencv_imgcodecs WRAP python java) ocv_define_module(ximgproc opencv_core opencv_imgproc opencv_calib3d opencv_imgcodecs opencv_video WRAP python java)
...@@ -328,3 +328,11 @@ year={2016}, ...@@ -328,3 +328,11 @@ year={2016},
publisher={Springer International Publishing}, publisher={Springer International Publishing},
pages={617--632}, pages={617--632},
} }
@inproceedings{Hu2017,
title={Robust interpolation of correspondences for large displacement optical flow},
author={Hu, Yinlin and Li, Yunsong and Song, Rui},
booktitle={IEEE Conference on Computer Vision and Pattern Recognition},
pages={481--489},
year={2017}
}
\ No newline at end of file
...@@ -77,6 +77,18 @@ estimator from @cite Revaud2015 and Fast Global Smoother as post-processing filt ...@@ -77,6 +77,18 @@ estimator from @cite Revaud2015 and Fast Global Smoother as post-processing filt
class CV_EXPORTS_W EdgeAwareInterpolator : public SparseMatchInterpolator class CV_EXPORTS_W EdgeAwareInterpolator : public SparseMatchInterpolator
{ {
public: public:
/** @brief Interface to provide a more elaborated cost map, i.e. edge map, for the edge-aware term.
* This implementation is based on a rather simple gradient-based edge map estimation.
* To used more complex edge map estimator (e.g. StructuredEdgeDetection that has been
* used in the original publication) that may lead to improved accuracies, the internal
* edge map estimation can be bypassed here.
* @param _costMap a type CV_32FC1 Mat is required.
* @see cv::ximgproc::createSuperpixelSLIC
*/
CV_WRAP virtual void setCostMap(const Mat & _costMap) = 0;
/** @brief Parameter to tune the approximate size of the superpixel used for oversegmentation.
* @see cv::ximgproc::createSuperpixelSLIC
*/
/** @brief K is a number of nearest-neighbor matches considered, when fitting a locally affine /** @brief K is a number of nearest-neighbor matches considered, when fitting a locally affine
model. Usually it should be around 128. However, lower values would make the interpolation model. Usually it should be around 128. However, lower values would make the interpolation
noticeably faster. noticeably faster.
...@@ -125,6 +137,132 @@ EdgeAwareInterpolator. ...@@ -125,6 +137,132 @@ EdgeAwareInterpolator.
CV_EXPORTS_W CV_EXPORTS_W
Ptr<EdgeAwareInterpolator> createEdgeAwareInterpolator(); Ptr<EdgeAwareInterpolator> createEdgeAwareInterpolator();
/** @brief Sparse match interpolation algorithm based on modified piecewise locally-weighted affine
* estimator called Robust Interpolation method of Correspondences or RIC from @cite Hu2017 and Variational
* and Fast Global Smoother as post-processing filter. The RICInterpolator is a extension of the EdgeAwareInterpolator.
* Main concept of this extension is an piece-wise affine model based on over-segmentation via SLIC superpixel estimation.
* The method contains an efficient propagation mechanism to estimate among the pieces-wise models.
*/
class CV_EXPORTS_W RICInterpolator : public SparseMatchInterpolator
{
public:
/** @brief K is a number of nearest-neighbor matches considered, when fitting a locally affine
*model for a superpixel segment. However, lower values would make the interpolation
*noticeably faster. The original implementation of @cite Hu2017 uses 32.
*/
CV_WRAP virtual void setK(int k = 32) = 0;
/** @copybrief setK
* @see setK
*/
CV_WRAP virtual int getK() const = 0;
/** @brief Interface to provide a more elaborated cost map, i.e. edge map, for the edge-aware term.
* This implementation is based on a rather simple gradient-based edge map estimation.
* To used more complex edge map estimator (e.g. StructuredEdgeDetection that has been
* used in the original publication) that may lead to improved accuracies, the internal
* edge map estimation can be bypassed here.
* @param costMap a type CV_32FC1 Mat is required.
* @see cv::ximgproc::createSuperpixelSLIC
*/
CV_WRAP virtual void setCostMap(const Mat & costMap) = 0;
/** @brief Get the internal cost, i.e. edge map, used for estimating the edge-aware term.
* @see setCostMap
*/
CV_WRAP virtual void setSuperpixelSize(int spSize = 15) = 0;
/** @copybrief setSuperpixelSize
* @see setSuperpixelSize
*/
CV_WRAP virtual int getSuperpixelSize() const = 0;
/** @brief Parameter defines the number of nearest-neighbor matches for each superpixel considered, when fitting a locally affine
*model.
*/
CV_WRAP virtual void setSuperpixelNNCnt(int spNN = 150) = 0;
/** @copybrief setSuperpixelNNCnt
* @see setSuperpixelNNCnt
*/
CV_WRAP virtual int getSuperpixelNNCnt() const = 0;
/** @brief Parameter to tune enforcement of superpixel smoothness factor used for oversegmentation.
* @see cv::ximgproc::createSuperpixelSLIC
*/
CV_WRAP virtual void setSuperpixelRuler(float ruler = 15.f) = 0;
/** @copybrief setSuperpixelRuler
* @see setSuperpixelRuler
*/
CV_WRAP virtual float getSuperpixelRuler() const = 0;
/** @brief Parameter to choose superpixel algorithm variant to use:
* - cv::ximgproc::SLICType SLIC segments image using a desired region_size (value: 100)
* - cv::ximgproc::SLICType SLICO will optimize using adaptive compactness factor (value: 101)
* - cv::ximgproc::SLICType MSLIC will optimize using manifold methods resulting in more content-sensitive superpixels (value: 102).
* @see cv::ximgproc::createSuperpixelSLIC
*/
CV_WRAP virtual void setSuperpixelMode(int mode = 100) = 0;
/** @copybrief setSuperpixelMode
* @see setSuperpixelMode
*/
CV_WRAP virtual int getSuperpixelMode() const = 0;
/** @brief Alpha is a parameter defining a global weight for transforming geodesic distance into weight.
*/
CV_WRAP virtual void setAlpha(float alpha = 0.7f) = 0;
/** @copybrief setAlpha
* @see setAlpha
*/
CV_WRAP virtual float getAlpha() const = 0;
/** @brief Parameter defining the number of iterations for piece-wise affine model estimation.
*/
CV_WRAP virtual void setModelIter(int modelIter = 4) = 0;
/** @copybrief setModelIter
* @see setModelIter
*/
CV_WRAP virtual int getModelIter() const = 0;
/** @brief Parameter to choose wether additional refinement of the piece-wise affine models is employed.
*/
CV_WRAP virtual void setRefineModels(bool refineModles = true) = 0;
/** @copybrief setRefineModels
* @see setRefineModels
*/
CV_WRAP virtual bool getRefineModels() const = 0;
/** @brief MaxFlow is a threshold to validate the predictions using a certain piece-wise affine model.
* If the prediction exceeds the treshold the translational model will be applied instead.
*/
CV_WRAP virtual void setMaxFlow(float maxFlow = 250.f) = 0;
/** @copybrief setMaxFlow
* @see setMaxFlow
*/
CV_WRAP virtual float getMaxFlow() const = 0;
/** @brief Parameter to choose wether the VariationalRefinement post-processing is employed.
*/
CV_WRAP virtual void setUseVariationalRefinement(bool use_variational_refinement = false) = 0;
/** @copybrief setUseVariationalRefinement
* @see setUseVariationalRefinement
*/
CV_WRAP virtual bool getUseVariationalRefinement() const = 0;
/** @brief Sets whether the fastGlobalSmootherFilter() post-processing is employed.
*/
CV_WRAP virtual void setUseGlobalSmootherFilter(bool use_FGS = true) = 0;
/** @copybrief setUseGlobalSmootherFilter
* @see setUseGlobalSmootherFilter
*/
CV_WRAP virtual bool getUseGlobalSmootherFilter() const = 0;
/** @brief Sets the respective fastGlobalSmootherFilter() parameter.
*/
CV_WRAP virtual void setFGSLambda(float lambda = 500.f) = 0;
/** @copybrief setFGSLambda
* @see setFGSLambda
*/
CV_WRAP virtual float getFGSLambda() const = 0;
/** @brief Sets the respective fastGlobalSmootherFilter() parameter.
*/
CV_WRAP virtual void setFGSSigma(float sigma = 1.5f) = 0;
/** @copybrief setFGSSigma
* @see setFGSSigma
*/
CV_WRAP virtual float getFGSSigma() const = 0;
};
/** @brief Factory method that creates an instance of the
RICInterpolator.
*/
CV_EXPORTS_W
Ptr<RICInterpolator> createRICInterpolator();
//! @} //! @}
} }
} }
......
...@@ -36,6 +36,7 @@ ...@@ -36,6 +36,7 @@
#include "precomp.hpp" #include "precomp.hpp"
#include "opencv2/ximgproc/sparse_match_interpolator.hpp" #include "opencv2/ximgproc/sparse_match_interpolator.hpp"
#include "opencv2/video.hpp"
#include <algorithm> #include <algorithm>
#include <vector> #include <vector>
#include "opencv2/core/hal/hal.hpp" #include "opencv2/core/hal/hal.hpp"
...@@ -57,9 +58,10 @@ struct SparseMatch ...@@ -57,9 +58,10 @@ struct SparseMatch
bool operator<(const SparseMatch& lhs,const SparseMatch& rhs); bool operator<(const SparseMatch& lhs,const SparseMatch& rhs);
void weightedLeastSquaresAffineFit(int* labels, float* weights, int count, float lambda, SparseMatch* matches, Mat& dst); static void computeGradientMagnitude(Mat& src, Mat& dst);
void generateHypothesis(int* labels, int count, RNG& rng, unsigned char* is_used, SparseMatch* matches, Mat& dst); static void weightedLeastSquaresAffineFit(int* labels, float* weights, int count, float lambda, const SparseMatch* matches, Mat& dst);
void verifyHypothesis(int* labels, float* weights, int count, SparseMatch* matches, float eps, float lambda, Mat& hypothesis_transform, Mat& old_transform, float& old_weighted_num_inliers); static void generateHypothesis(int* labels, int count, RNG& rng, unsigned char* is_used, SparseMatch* matches, Mat& dst);
static void verifyHypothesis(int* labels, float* weights, int count, SparseMatch* matches, float eps, float lambda, Mat& hypothesis_transform, Mat& old_transform, float& old_weighted_num_inliers);
struct node struct node
{ {
...@@ -69,6 +71,8 @@ struct node ...@@ -69,6 +71,8 @@ struct node
node(int l,float d): dist(d), label(l) {} node(int l,float d): dist(d), label(l) {}
}; };
class EdgeAwareInterpolatorImpl CV_FINAL : public EdgeAwareInterpolator class EdgeAwareInterpolatorImpl CV_FINAL : public EdgeAwareInterpolator
{ {
public: public:
...@@ -76,14 +80,14 @@ public: ...@@ -76,14 +80,14 @@ public:
void interpolate(InputArray from_image, InputArray from_points, InputArray to_image, InputArray to_points, OutputArray dense_flow) CV_OVERRIDE; void interpolate(InputArray from_image, InputArray from_points, InputArray to_image, InputArray to_points, OutputArray dense_flow) CV_OVERRIDE;
protected: protected:
int w,h;
int match_num; int match_num;
int w, h;
//internal buffers: //internal buffers:
vector<node>* g; vector<node>* g;
Mat labels;
Mat NNlabels; Mat NNlabels;
Mat NNdistances; Mat NNdistances;
Mat labels;
Mat costMap;
//tunable parameters: //tunable parameters:
float lambda; float lambda;
int k; int k;
...@@ -93,15 +97,14 @@ protected: ...@@ -93,15 +97,14 @@ protected:
float fgs_sigma; float fgs_sigma;
// static parameters: // static parameters:
static const int distance_transform_num_iter = 1;
static const int ransac_interpolation_num_iter = 1; static const int ransac_interpolation_num_iter = 1;
static const int distance_transform_num_iter = 1;
float regularization_coef; float regularization_coef;
static const int ransac_num_stripes = 4; static const int ransac_num_stripes = 4;
RNG rngs[ransac_num_stripes]; RNG rngs[ransac_num_stripes];
void init(); void init();
void preprocessData(Mat& src, vector<SparseMatch>& matches); void preprocessData(Mat& src, vector<SparseMatch>& matches);
void computeGradientMagnitude(Mat& src, Mat& dst);
void geodesicDistanceTransform(Mat& distances, Mat& cost_map); void geodesicDistanceTransform(Mat& distances, Mat& cost_map);
void buildGraph(Mat& distances, Mat& cost_map); void buildGraph(Mat& distances, Mat& cost_map);
void ransacInterpolation(vector<SparseMatch>& matches, Mat& dst_dense_flow); void ransacInterpolation(vector<SparseMatch>& matches, Mat& dst_dense_flow);
...@@ -133,6 +136,7 @@ protected: ...@@ -133,6 +136,7 @@ protected:
}; };
public: public:
void setCostMap(const Mat & _costMap) CV_OVERRIDE { _costMap.copyTo(costMap); }
void setK(int _k) CV_OVERRIDE {k=_k;} void setK(int _k) CV_OVERRIDE {k=_k;}
int getK() CV_OVERRIDE {return k;} int getK() CV_OVERRIDE {return k;}
void setSigma(float _sigma) CV_OVERRIDE {sigma=_sigma;} void setSigma(float _sigma) CV_OVERRIDE {sigma=_sigma;}
...@@ -156,6 +160,7 @@ void EdgeAwareInterpolatorImpl::init() ...@@ -156,6 +160,7 @@ void EdgeAwareInterpolatorImpl::init()
fgs_lambda = 500.0f; fgs_lambda = 500.0f;
fgs_sigma = 1.5f; fgs_sigma = 1.5f;
regularization_coef = 0.01f; regularization_coef = 0.01f;
costMap = Mat();
} }
Ptr<EdgeAwareInterpolatorImpl> EdgeAwareInterpolatorImpl::create() Ptr<EdgeAwareInterpolatorImpl> EdgeAwareInterpolatorImpl::create()
...@@ -201,13 +206,13 @@ void EdgeAwareInterpolatorImpl::interpolate(InputArray from_image, InputArray fr ...@@ -201,13 +206,13 @@ void EdgeAwareInterpolatorImpl::interpolate(InputArray from_image, InputArray fr
if(use_post_proc) if(use_post_proc)
fastGlobalSmootherFilter(src,dst,dst,fgs_lambda,fgs_sigma); fastGlobalSmootherFilter(src,dst,dst,fgs_lambda,fgs_sigma);
costMap.release();
delete[] g; delete[] g;
} }
void EdgeAwareInterpolatorImpl::preprocessData(Mat& src, vector<SparseMatch>& matches) void EdgeAwareInterpolatorImpl::preprocessData(Mat& src, vector<SparseMatch>& matches)
{ {
Mat distances(h,w,CV_32F); Mat distances(h,w,CV_32F);
Mat cost_map (h,w,CV_32F);
distances = Scalar(INF); distances = Scalar(INF);
int x,y; int x,y;
...@@ -220,56 +225,26 @@ void EdgeAwareInterpolatorImpl::preprocessData(Mat& src, vector<SparseMatch>& ma ...@@ -220,56 +225,26 @@ void EdgeAwareInterpolatorImpl::preprocessData(Mat& src, vector<SparseMatch>& ma
labels.at<int>(y,x) = (int)i; labels.at<int>(y,x) = (int)i;
} }
computeGradientMagnitude(src,cost_map); if (costMap.empty())
cost_map = (1000.0f-lambda) + lambda*cost_map;
geodesicDistanceTransform(distances,cost_map);
buildGraph(distances,cost_map);
parallel_for_(Range(0,getNumThreads()),GetKNNMatches_ParBody(*this,getNumThreads()));
}
void EdgeAwareInterpolatorImpl::computeGradientMagnitude(Mat& src, Mat& dst)
{
Mat dx,dy;
Sobel(src, dx, CV_16S, 1, 0);
Sobel(src, dy, CV_16S, 0, 1);
float norm_coef = src.channels()*4*255.0f;
if(src.channels()==1)
{ {
for(int i=0;i<h;i++) costMap.create(h, w, CV_32FC1);
{ computeGradientMagnitude(src, costMap);
short* dx_row = dx.ptr<short>(i);
short* dy_row = dy.ptr<short>(i);
float* dst_row = dst.ptr<float>(i);
for(int j=0;j<w;j++)
dst_row[j] = ((float)abs(dx_row[j])+abs(dy_row[j]))/norm_coef;
}
} }
else else
{ CV_Assert(costMap.cols == w && costMap.rows == h);
for(int i=0;i<h;i++) costMap = (1000.0f-lambda) + lambda* costMap;
{ geodesicDistanceTransform(distances, costMap);
Vec3s* dx_row = dx.ptr<Vec3s>(i); buildGraph(distances, costMap);
Vec3s* dy_row = dy.ptr<Vec3s>(i); parallel_for_(Range(0,getNumThreads()),GetKNNMatches_ParBody(*this,getNumThreads()));
float* dst_row = dst.ptr<float>(i);
for(int j=0;j<w;j++)
dst_row[j] = (float)(abs(dx_row[j][0])+abs(dy_row[j][0])+
abs(dx_row[j][1])+abs(dy_row[j][1])+
abs(dx_row[j][2])+abs(dy_row[j][2]))/norm_coef;
}
}
} }
void EdgeAwareInterpolatorImpl::geodesicDistanceTransform(Mat& distances, Mat& cost_map) void EdgeAwareInterpolatorImpl::geodesicDistanceTransform(Mat& distances, Mat& cost_map)
{ {
float c1 = 1.0f/2.0f; float c1 = 1.0f / 2.0f;
float c2 = sqrt(2.0f)/2.0f; float c2 = sqrt(2.0f) / 2.0f;
float d = 0.0f; float d = 0.0f;
int i,j; int i, j;
float *dist_row, *cost_row; float *dist_row, *cost_row;
float *dist_row_prev, *cost_row_prev; float *dist_row_prev, *cost_row_prev;
int *label_row; int *label_row;
int *label_row_prev; int *label_row_prev;
...@@ -282,74 +257,74 @@ void EdgeAwareInterpolatorImpl::geodesicDistanceTransform(Mat& distances, Mat& c ...@@ -282,74 +257,74 @@ void EdgeAwareInterpolatorImpl::geodesicDistanceTransform(Mat& distances, Mat& c
cur_label = prev_label;}\ cur_label = prev_label;}\
} }
for(int it=0;it<distance_transform_num_iter;it++) for (int it = 0; it < distance_transform_num_iter; it++)
{ {
//first pass (left-to-right, top-to-bottom): //first pass (left-to-right, top-to-bottom):
dist_row = distances.ptr<float>(0); dist_row = distances.ptr<float>(0);
label_row = labels.ptr<int>(0); label_row = labels.ptr<int>(0);
cost_row = cost_map.ptr<float>(0); cost_row = cost_map.ptr<float>(0);
for(j=1;j<w;j++) for (j = 1; j < w; j++)
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row[j-1],label_row[j-1],cost_row[j-1],c1); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row[j - 1], label_row[j - 1], cost_row[j - 1], c1);
for(i=1;i<h;i++) for (i = 1; i < h; i++)
{ {
dist_row = distances.ptr<float>(i); dist_row = distances.ptr<float>(i);
dist_row_prev = distances.ptr<float>(i-1); dist_row_prev = distances.ptr<float>(i - 1);
label_row = labels.ptr<int>(i); label_row = labels.ptr<int>(i);
label_row_prev = labels.ptr<int>(i-1); label_row_prev = labels.ptr<int>(i - 1);
cost_row = cost_map.ptr<float>(i); cost_row = cost_map.ptr<float>(i);
cost_row_prev = cost_map.ptr<float>(i-1); cost_row_prev = cost_map.ptr<float>(i - 1);
j=0; j = 0;
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j] ,label_row_prev[j] ,cost_row_prev[j] ,c1); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j+1],label_row_prev[j+1],cost_row_prev[j+1],c2); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j + 1], label_row_prev[j + 1], cost_row_prev[j + 1], c2);
j++; j++;
for(;j<w-1;j++) for (; j < w - 1; j++)
{ {
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row[j-1] ,label_row[j-1] ,cost_row[j-1] ,c1); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row[j - 1], label_row[j - 1], cost_row[j - 1], c1);
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j-1],label_row_prev[j-1],cost_row_prev[j-1],c2); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j - 1], label_row_prev[j - 1], cost_row_prev[j - 1], c2);
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j] ,label_row_prev[j] ,cost_row_prev[j] ,c1); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j+1],label_row_prev[j+1],cost_row_prev[j+1],c2); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j + 1], label_row_prev[j + 1], cost_row_prev[j + 1], c2);
} }
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row[j-1] ,label_row[j-1] ,cost_row[j-1] ,c1); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row[j - 1], label_row[j - 1], cost_row[j - 1], c1);
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j-1],label_row_prev[j-1],cost_row_prev[j-1],c2); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j - 1], label_row_prev[j - 1], cost_row_prev[j - 1], c2);
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j] ,label_row_prev[j] ,cost_row_prev[j] ,c1); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
} }
//second pass (right-to-left, bottom-to-top): //second pass (right-to-left, bottom-to-top):
dist_row = distances.ptr<float>(h-1); dist_row = distances.ptr<float>(h - 1);
label_row = labels.ptr<int>(h-1); label_row = labels.ptr<int>(h - 1);
cost_row = cost_map.ptr<float>(h-1); cost_row = cost_map.ptr<float>(h - 1);
for(j=w-2;j>=0;j--) for (j = w - 2; j >= 0; j--)
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row[j+1],label_row[j+1],cost_row[j+1],c1); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row[j + 1], label_row[j + 1], cost_row[j + 1], c1);
for(i=h-2;i>=0;i--) for (i = h - 2; i >= 0; i--)
{ {
dist_row = distances.ptr<float>(i); dist_row = distances.ptr<float>(i);
dist_row_prev = distances.ptr<float>(i+1); dist_row_prev = distances.ptr<float>(i + 1);
label_row = labels.ptr<int>(i); label_row = labels.ptr<int>(i);
label_row_prev = labels.ptr<int>(i+1); label_row_prev = labels.ptr<int>(i + 1);
cost_row = cost_map.ptr<float>(i); cost_row = cost_map.ptr<float>(i);
cost_row_prev = cost_map.ptr<float>(i+1); cost_row_prev = cost_map.ptr<float>(i + 1);
j=w-1; j = w - 1;
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j] ,label_row_prev[j] ,cost_row_prev[j] ,c1); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j-1],label_row_prev[j-1],cost_row_prev[j-1],c2); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j - 1], label_row_prev[j - 1], cost_row_prev[j - 1], c2);
j--; j--;
for(;j>0;j--) for (; j > 0; j--)
{ {
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row[j+1] ,label_row[j+1] ,cost_row[j+1] ,c1); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row[j + 1], label_row[j + 1], cost_row[j + 1], c1);
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j+1],label_row_prev[j+1],cost_row_prev[j+1],c2); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j + 1], label_row_prev[j + 1], cost_row_prev[j + 1], c2);
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j] ,label_row_prev[j] ,cost_row_prev[j] ,c1); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j-1],label_row_prev[j-1],cost_row_prev[j-1],c2); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j - 1], label_row_prev[j - 1], cost_row_prev[j - 1], c2);
} }
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row[j+1] ,label_row[j+1] ,cost_row[j+1] ,c1); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row[j + 1], label_row[j + 1], cost_row[j + 1], c1);
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j+1],label_row_prev[j+1],cost_row_prev[j+1],c2); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j + 1], label_row_prev[j + 1], cost_row_prev[j + 1], c2);
CHECK(dist_row[j],label_row[j],cost_row[j],dist_row_prev[j] ,label_row_prev[j] ,cost_row_prev[j] ,c1); CHECK(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
} }
} }
#undef CHECK #undef CHECK
...@@ -624,7 +599,7 @@ void EdgeAwareInterpolatorImpl::GetKNNMatches_ParBody::operator() (const Range& ...@@ -624,7 +599,7 @@ void EdgeAwareInterpolatorImpl::GetKNNMatches_ParBody::operator() (const Range&
delete[] expanded_flag; delete[] expanded_flag;
} }
void weightedLeastSquaresAffineFit(int* labels, float* weights, int count, float lambda, SparseMatch* matches, Mat& dst) static void weightedLeastSquaresAffineFit(int* labels, float* weights, int count, float lambda, const SparseMatch* matches, Mat& dst)
{ {
double sa[6][6]={{0.}}, sb[6]={0.}; double sa[6][6]={{0.}}, sb[6]={0.};
Mat A (6, 6, CV_64F, &sa[0][0]), Mat A (6, 6, CV_64F, &sa[0][0]),
...@@ -671,7 +646,7 @@ void weightedLeastSquaresAffineFit(int* labels, float* weights, int count, float ...@@ -671,7 +646,7 @@ void weightedLeastSquaresAffineFit(int* labels, float* weights, int count, float
MM.reshape(2,3).convertTo(dst,CV_32F); MM.reshape(2,3).convertTo(dst,CV_32F);
} }
void generateHypothesis(int* labels, int count, RNG& rng, unsigned char* is_used, SparseMatch* matches, Mat& dst) static void generateHypothesis(int* labels, int count, RNG& rng, unsigned char* is_used, SparseMatch* matches, Mat& dst)
{ {
int idx; int idx;
Point2f src_points[3]; Point2f src_points[3];
...@@ -702,7 +677,7 @@ void generateHypothesis(int* labels, int count, RNG& rng, unsigned char* is_used ...@@ -702,7 +677,7 @@ void generateHypothesis(int* labels, int count, RNG& rng, unsigned char* is_used
getAffineTransform(src_points,dst_points).convertTo(dst,CV_32F); getAffineTransform(src_points,dst_points).convertTo(dst,CV_32F);
} }
void verifyHypothesis(int* labels, float* weights, int count, SparseMatch* matches, float eps, float lambda, Mat& hypothesis_transform, Mat& old_transform, float& old_weighted_num_inliers) static void verifyHypothesis(int* labels, float* weights, int count, SparseMatch* matches, float eps, float lambda, Mat& hypothesis_transform, Mat& old_transform, float& old_weighted_num_inliers)
{ {
float* tr = hypothesis_transform.ptr<float>(0); float* tr = hypothesis_transform.ptr<float>(0);
Point2f a,b; Point2f a,b;
...@@ -724,6 +699,41 @@ void verifyHypothesis(int* labels, float* weights, int count, SparseMatch* match ...@@ -724,6 +699,41 @@ void verifyHypothesis(int* labels, float* weights, int count, SparseMatch* match
} }
} }
static void computeGradientMagnitude(Mat& src, Mat& dst)
{
Mat dx, dy;
Sobel(src, dx, CV_16S, 1, 0);
Sobel(src, dy, CV_16S, 0, 1);
float norm_coef = src.channels() * 4 * 255.0f;
if (src.channels() == 1)
{
for (int i = 0; i < src.rows; i++)
{
short* dx_row = dx.ptr<short>(i);
short* dy_row = dy.ptr<short>(i);
float* dst_row = dst.ptr<float>(i);
for (int j = 0; j < src.cols; j++)
dst_row[j] = ((float)abs(dx_row[j]) + abs(dy_row[j])) / norm_coef;
}
}
else
{
for (int i = 0; i < src.rows; i++)
{
Vec3s* dx_row = dx.ptr<Vec3s>(i);
Vec3s* dy_row = dy.ptr<Vec3s>(i);
float* dst_row = dst.ptr<float>(i);
for (int j = 0; j < src.cols; j++)
dst_row[j] = (float)(abs(dx_row[j][0]) + abs(dy_row[j][0]) +
abs(dx_row[j][1]) + abs(dy_row[j][1]) +
abs(dx_row[j][2]) + abs(dy_row[j][2])) / norm_coef;
}
}
}
EdgeAwareInterpolatorImpl::RansacInterpolation_ParBody::RansacInterpolation_ParBody(EdgeAwareInterpolatorImpl& _inst, Mat* _transforms, float* _weighted_inlier_nums, float* _eps, SparseMatch* _matches, int _num_stripes, int _inc): EdgeAwareInterpolatorImpl::RansacInterpolation_ParBody::RansacInterpolation_ParBody(EdgeAwareInterpolatorImpl& _inst, Mat* _transforms, float* _weighted_inlier_nums, float* _eps, SparseMatch* _matches, int _num_stripes, int _inc):
inst(&_inst), transforms(_transforms), weighted_inlier_nums(_weighted_inlier_nums), eps(_eps), matches(_matches), num_stripes(_num_stripes), inc(_inc) inst(&_inst), transforms(_transforms), weighted_inlier_nums(_weighted_inlier_nums), eps(_eps), matches(_matches), num_stripes(_num_stripes), inc(_inc)
{ {
...@@ -877,5 +887,1006 @@ bool operator<(const SparseMatch& lhs,const SparseMatch& rhs) ...@@ -877,5 +887,1006 @@ bool operator<(const SparseMatch& lhs,const SparseMatch& rhs)
return (lhs.reference_image_pos.x<rhs.reference_image_pos.x); return (lhs.reference_image_pos.x<rhs.reference_image_pos.x);
} }
class RICInterpolatorImpl CV_FINAL : public RICInterpolator
{
public:
static Ptr<RICInterpolatorImpl> create();
void interpolate(InputArray from_image, InputArray from_points, InputArray to_image, InputArray to_points, OutputArray dense_flow) CV_OVERRIDE;
protected:
// internal buffers
int match_num;
vector<vector<node>> g;
Mat NNlabels;
Mat NNdistances;
Mat labels;
Mat costMap;
static const int distance_transform_num_iter = 1;
float lambda;
//tunable parameters:
int max_neighbors;
float alpha;
int sp_size;
int sp_nncnt;
float sp_ruler;
int model_iter;
bool refine_models;
bool use_variational_refinement;
float cost_suffix;
float max_flow;
bool use_global_smoother_filter;
float fgs_lambda;
float fgs_sigma;
SLICType slic_type;
void init();
void buildGraph(Mat& distances, Mat& cost_map);
void geodesicDistanceTransform(Mat& distances, Mat& cost_map);
int overSegmentaion(const Mat & img, Mat & outLabels, const int spSize);
void superpixelNeighborConstruction(const Mat & labels, int labelCnt, Mat& outNeighbor);
void superpixelLayoutAnalysis(const Mat & labels, int labelCnt, Mat & outCenterPositions, Mat & outNodeItemLists);
void findSupportMatches(vector<int> & srcIds, int srcCnt, int supportCnt, Mat & matNN,
Mat & matNNDis, vector<int> & outSupportIds, vector<float> & outSupportDis);
float GetWeightFromDistance(float dis);
int PropagateModels(int spCnt, Mat & spNN, vector<int> & supportMatchIds, vector<float> & supportMatchDis, int supportCnt,
const vector<SparseMatch> &inputMatches, Mat & outModels);
float HypothesisEvaluation(const Mat & inModel, const int * matNodes, const float * matDis, int matCnt, const vector<SparseMatch> & inputMatches, Mat & outInLier);
int HypothesisGeneration(int* matNodes, int matCnt, const vector<SparseMatch> & inputMatches, Mat & outModel);
public:
void setCostMap(const Mat & _costMap) CV_OVERRIDE { _costMap.copyTo(costMap); }
void setK(int val) CV_OVERRIDE { max_neighbors = val; }
int getK() const CV_OVERRIDE { return max_neighbors; }
void setSuperpixelSize(int val) CV_OVERRIDE { sp_size = val; }
int getSuperpixelSize() const CV_OVERRIDE { return sp_size; }
void setSuperpixelNNCnt(int val) CV_OVERRIDE { sp_nncnt = val; }
int getSuperpixelNNCnt() const CV_OVERRIDE { return sp_nncnt; }
void setSuperpixelRuler(float val) CV_OVERRIDE { sp_ruler = val; }
float getSuperpixelRuler() const CV_OVERRIDE { return sp_ruler; }
void setSuperpixelMode(int val) CV_OVERRIDE
{
slic_type = static_cast<SLICType>(val);
CV_Assert(slic_type == SLICO || slic_type == SLIC || slic_type == MSLIC);
}
int getSuperpixelMode() const CV_OVERRIDE { return slic_type; }
void setAlpha(float val) CV_OVERRIDE { alpha = val; }
float getAlpha() const CV_OVERRIDE { return alpha; }
void setModelIter(int val) CV_OVERRIDE { model_iter = val; }
int getModelIter() const CV_OVERRIDE { return model_iter; }
void setRefineModels(bool val) CV_OVERRIDE { refine_models = static_cast<int>(val); }
bool getRefineModels() const CV_OVERRIDE { return refine_models; }
void setMaxFlow(float val) CV_OVERRIDE { max_flow = val; }
float getMaxFlow() const CV_OVERRIDE { return max_flow; }
void setUseVariationalRefinement(bool val) CV_OVERRIDE { use_variational_refinement = val; }
bool getUseVariationalRefinement() const CV_OVERRIDE { return use_variational_refinement; }
void setUseGlobalSmootherFilter(bool val) CV_OVERRIDE { use_global_smoother_filter = val; }
bool getUseGlobalSmootherFilter() const CV_OVERRIDE { return use_global_smoother_filter; }
void setFGSLambda(float _lambda) CV_OVERRIDE { fgs_lambda = _lambda; }
float getFGSLambda() const CV_OVERRIDE { return fgs_lambda; }
void setFGSSigma(float _sigma) CV_OVERRIDE { fgs_sigma = _sigma; }
float getFGSSigma() const CV_OVERRIDE { return fgs_sigma; }
};
Ptr<RICInterpolatorImpl> RICInterpolatorImpl::create()
{
auto eai = makePtr<RICInterpolatorImpl>();
eai->init();
return eai;
}
void RICInterpolatorImpl::init()
{
max_neighbors = 32;
alpha = 0.7f;
lambda = 999.0f;
sp_size = 15;
sp_nncnt = 150;
sp_ruler = 15.f;
model_iter = 4;
refine_models = true;
use_variational_refinement = false;
cost_suffix = 0.001f;
max_flow = 250.f;
use_global_smoother_filter = true;
fgs_lambda = 500.0f;
fgs_sigma = 1.5f;
slic_type = SLIC;
costMap = Mat();
}
struct MinHeap
{
public:
MinHeap(int size)
{
//memset(this, 0, sizeof(*this));
Init(size);
}
int Init(int size)
{
m_index.resize(size);
m_weight.resize(size);
m_size = size;
m_validSize = 0;
return 0;
}
int Push(float index, float weight)
{
if (m_validSize >= m_size)
{
CV_Error(CV_StsOutOfRange, " m_validSize >= m_size this problem can be resolved my decreasig k parameter");
}
m_index[m_validSize] = index;
m_weight[m_validSize] = weight;
m_validSize++;
int i = m_validSize - 1;
while (prior(m_weight[i], m_weight[(i - 1) / 2])) {
swap(m_weight[i], m_weight[(i - 1) / 2]);
swap(m_index[i], m_index[(i - 1) / 2]);
i = (i - 1) / 2; // jump up to the parent
}
return i;
}
float Pop(float* weight = NULL)
{
if (m_validSize == 0) {
return -1;
}
if (weight) {
*weight = m_weight[0];
}
float outIdx = m_index[0];
// use the last item to overwrite the first
m_index[0] = m_index[m_validSize - 1];
m_weight[0] = m_weight[m_validSize - 1];
m_validSize--;
// adjust the heap from top to bottom
float rawIdx = m_index[0];
float rawWt = m_weight[0];
int candiPos = 0; // the root
int i = 1; // left child of the root
while (i < m_validSize) {
// test right child
if (i + 1 < m_validSize && prior(m_weight[i + 1], m_weight[i])) {
i++;
}
if (prior(rawWt, m_weight[i])) {
break;
}
m_index[candiPos] = m_index[i];
m_weight[candiPos] = m_weight[i];
candiPos = i;
i = (i + 1) * 2 - 1; // left child
}
m_index[candiPos] = rawIdx;
m_weight[candiPos] = rawWt;
return outIdx;
}
void Clear()
{
m_validSize = 0;
}
int Size()
{
return m_validSize;
}
private:
inline bool prior(float w1, float w2)
{
return w1 < w2;
}
vector<float> m_index;
vector<float> m_weight;
int m_size;
int m_validSize;
};
void RICInterpolatorImpl::interpolate(InputArray from_image, InputArray from_points, InputArray to_image, InputArray to_points, OutputArray dense_flow)
{
CV_Assert(!from_image.empty());
CV_Assert(from_image.depth() == CV_8U);
CV_Assert((from_image.channels() == 3 || from_image.channels() == 1));
CV_Assert(use_variational_refinement == false || !to_image.empty());
CV_Assert(use_variational_refinement == false || to_image.depth() == CV_8U);
CV_Assert(use_variational_refinement == false || to_image.channels() == 3 || to_image.channels() == 1);
CV_Assert(!from_points.empty() && from_points.isVector());
CV_Assert(!to_points.empty() && to_points.isVector());
CV_Assert(from_points.sameSize(to_points));
vector<Point2f> from_vector = *(const vector<Point2f>*)from_points.getObj();
vector<Point2f> to_vector = *(const vector<Point2f>*)to_points.getObj();
vector<SparseMatch> matches_vector(from_vector.size());
for (unsigned int i = 0; i < from_vector.size(); i++)
matches_vector[i] = SparseMatch(from_vector[i], to_vector[i]);
match_num = static_cast<int>(from_vector.size());
Mat src = from_image.getMat();
Size src_size = src.size();
labels = Mat(src_size, CV_32SC1);
labels.setTo(-1);
NNlabels = Mat(match_num, max_neighbors, CV_32S);
NNlabels = Scalar(-1);
NNdistances = Mat(match_num, max_neighbors, CV_32F);
NNdistances = Scalar(0.0f);
Mat matDistanceMap(src_size, CV_32FC1);
matDistanceMap.setTo(1e10);
if (costMap.empty())
{
costMap.create(src_size, CV_32FC1);
computeGradientMagnitude(src, costMap);
}
else
CV_Assert(costMap.rows == src.rows && costMap.cols == src.cols );
costMap = (1000.0f - lambda) + lambda * costMap;
for (unsigned int i = 0; i < matches_vector.size(); i++)
{
const SparseMatch & p = matches_vector[i];
Point pos(static_cast<int>(p.reference_image_pos.x), static_cast<int>(p.reference_image_pos.y));
labels.at<int>(pos) = i;
matDistanceMap.at<float>(pos) = costMap.at<float>(pos);
}
geodesicDistanceTransform(matDistanceMap, costMap);
g.resize(match_num);
buildGraph(matDistanceMap, costMap);
parallel_for_(Range(0, getNumThreads()), [&](const Range & range)
{
int stripe_sz = (int)ceil(match_num / (double)getNumThreads());
int start = std::min(range.start * stripe_sz, match_num);
int end = std::min(range.end * stripe_sz, match_num);
nodeHeap q((int)match_num);
int num_expanded_vertices;
vector<unsigned int> expanded_flag(match_num);
node* neighbors;
for (int i = start; i < end; i++)
{
if (g[i].empty())
continue;
num_expanded_vertices = 0;
fill(expanded_flag.begin(), expanded_flag.end(), 0);
q.clear();
q.add(node((int)i, 0.0f));
int* NNlabels_row = NNlabels.ptr<int>(i);
float* NNdistances_row = NNdistances.ptr<float>(i);
while (num_expanded_vertices < max_neighbors && !q.empty())
{
node vert_for_expansion = q.getMin();
expanded_flag[vert_for_expansion.label] = 1;
//write the expanded vertex to the dst:
NNlabels_row[num_expanded_vertices] = vert_for_expansion.label;
NNdistances_row[num_expanded_vertices] = vert_for_expansion.dist;
num_expanded_vertices++;
//update the heap:
neighbors = &g[vert_for_expansion.label].front();
for (int j = 0; j < (int)g[vert_for_expansion.label].size(); j++)
{
if (!expanded_flag[neighbors[j].label])
q.updateNode(node(neighbors[j].label, vert_for_expansion.dist + neighbors[j].dist));
}
}
}
});
Mat spLabels;
Mat spNN;
Mat spPos;
Mat spItems;
int spCnt = overSegmentaion(src, spLabels, sp_size);
superpixelNeighborConstruction(spLabels, spCnt, spNN);
superpixelLayoutAnalysis(spLabels, spCnt, spPos, spItems);
vector<int> srcMatchIds(spCnt);
for (int i = 0; i < spCnt; i++)
{
Point pos = static_cast<Point>(spPos.at<Point2f>(i) + Point2f(0.5f,0.5f));
pos.x = MIN(labels.cols - 1, pos.x);
pos.y = MIN(labels.rows - 1, pos.y);
srcMatchIds[i] = labels.at<int>(pos);
}
int supportCnt = sp_nncnt;
vector<int> supportMatchIds(spCnt*supportCnt); // support matches for each superpixel
vector<float> supportMatchDis(spCnt*supportCnt);
findSupportMatches(srcMatchIds, spCnt, supportCnt, NNlabels, NNdistances, supportMatchIds, supportMatchDis);
Mat transModels(spCnt,6, CV_32FC1);
Mat fitModels(spCnt, 6, CV_32FC1);
Mat rawModel(1, 6, CV_32FC1);
rawModel.setTo(0);
rawModel.at<float>(0) = 1;
rawModel.at<float>(4) = 1;
for (int i = 0; i < spCnt; i++) {
int matId = supportMatchIds[i*supportCnt + 0];
const SparseMatch & p = matches_vector[matId];
float u = p.target_image_pos.x - p.reference_image_pos.x;
float v = p.target_image_pos.y - p.reference_image_pos.y;
rawModel.copyTo(transModels.row(i));
transModels.at<float>(i,2) = u;
transModels.at<float>(i,5) = v;
transModels.row(i).copyTo(fitModels.row(i));
}
PropagateModels(spCnt, spNN, supportMatchIds, supportMatchDis, supportCnt, matches_vector, fitModels);
dense_flow.create(from_image.size(), CV_32FC2);
Mat U = Mat(src.rows, src.cols, CV_32FC1);
Mat V = Mat(src.rows, src.cols, CV_32FC1);
for (int i = 0; i < spCnt; i++) {
for (int k = 0; k < spItems.cols; k++) {
int x = spItems.at<Point>(i,k).x;
int y = spItems.at<Point>(i,k).y;
if (x < 0 || y < 0) {
break;
}
float fx = fitModels.at<float>(i, 0) * x + fitModels.at<float>(i, 1) * y + fitModels.at<float>(i, 2);
float fy = fitModels.at<float>(i, 3) * x + fitModels.at<float>(i, 4) * y + fitModels.at<float>(i, 5);
//cout << fitModels << endl;
U.at<float>(y, x) = fx - x;
V.at<float>(y, x) = fy - y;
if (abs(fx - x) > max_flow || abs(fy - y) > max_flow)
{
// use the translational model directly
fx = transModels.at<float>(i, 0) * x + transModels.at<float>(i, 1) * y + transModels.at<float>(i, 2);
fy = transModels.at<float>(i, 3) * x + transModels.at<float>(i, 4) * y + transModels.at<float>(i, 5);
U.at<float>(y, x) = fx - x;
V.at<float>(y, x) = fy - y;
}
}
}
Mat dst;
Mat prevGrey, currGrey;
if (use_variational_refinement)
{
Mat src2 = to_image.getMat();
cv::medianBlur(U, U, 3);
cv::medianBlur(V, V, 3);
Ptr<VariationalRefinement> variationalrefine = VariationalRefinement::create();
cvtColor(src, prevGrey, COLOR_BGR2GRAY);
cvtColor(src2, currGrey, COLOR_BGR2GRAY);
variationalrefine->setOmega(1.9f);
variationalrefine->calcUV(prevGrey, currGrey, U,V);
}
Mat UV[2] = { U,V };
merge(UV, 2, dst);
if (use_global_smoother_filter)
{
if (prevGrey.empty())
cvtColor(src, prevGrey, COLOR_BGR2GRAY);
fastGlobalSmootherFilter(prevGrey, dst, dst, fgs_lambda, fgs_sigma);
}
dst.copyTo(dense_flow.getMat());
costMap.release();
}
void RICInterpolatorImpl::geodesicDistanceTransform(Mat& distances, Mat& cost_map)
{
float c1 = 1.0f / 2.0f;
float c2 = sqrt(2.0f) / 2.0f;
float d = 0.0f;
int i, j;
float *dist_row, *cost_row;
float *dist_row_prev, *cost_row_prev;
int *label_row;
int *label_row_prev;
#define CHK_GD(cur_dist,cur_label,cur_cost,prev_dist,prev_label,prev_cost,coef)\
{\
d = prev_dist + coef*(cur_cost+prev_cost);\
if(cur_dist>d){\
cur_dist=d;\
cur_label = prev_label;}\
}
for (int it = 0; it < distance_transform_num_iter; it++)
{
//first pass (left-to-right, top-to-bottom):
dist_row = distances.ptr<float>(0);
label_row = labels.ptr<int>(0);
cost_row = cost_map.ptr<float>(0);
for (j = 1; j < distances.cols; j++)
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row[j - 1], label_row[j - 1], cost_row[j - 1], c1);
for (i = 1; i < distances.rows; i++)
{
dist_row = distances.ptr<float>(i);
dist_row_prev = distances.ptr<float>(i - 1);
label_row = labels.ptr<int>(i);
label_row_prev = labels.ptr<int>(i - 1);
cost_row = cost_map.ptr<float>(i);
cost_row_prev = cost_map.ptr<float>(i - 1);
j = 0;
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j + 1], label_row_prev[j + 1], cost_row_prev[j + 1], c2);
j++;
for (; j < distances.cols - 1; j++)
{
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row[j - 1], label_row[j - 1], cost_row[j - 1], c1);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j - 1], label_row_prev[j - 1], cost_row_prev[j - 1], c2);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j + 1], label_row_prev[j + 1], cost_row_prev[j + 1], c2);
}
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row[j - 1], label_row[j - 1], cost_row[j - 1], c1);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j - 1], label_row_prev[j - 1], cost_row_prev[j - 1], c2);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
}
//second pass (right-to-left, bottom-to-top):
dist_row = distances.ptr<float>(distances.rows - 1);
label_row = labels.ptr<int>(distances.rows - 1);
cost_row = cost_map.ptr<float>(distances.rows - 1);
for (j = distances.cols - 2; j >= 0; j--)
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row[j + 1], label_row[j + 1], cost_row[j + 1], c1);
for (i = distances.rows - 2; i >= 0; i--)
{
dist_row = distances.ptr<float>(i);
dist_row_prev = distances.ptr<float>(i + 1);
label_row = labels.ptr<int>(i);
label_row_prev = labels.ptr<int>(i + 1);
cost_row = cost_map.ptr<float>(i);
cost_row_prev = cost_map.ptr<float>(i + 1);
j = distances.cols - 1;
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j - 1], label_row_prev[j - 1], cost_row_prev[j - 1], c2);
j--;
for (; j > 0; j--)
{
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row[j + 1], label_row[j + 1], cost_row[j + 1], c1);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j + 1], label_row_prev[j + 1], cost_row_prev[j + 1], c2);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j - 1], label_row_prev[j - 1], cost_row_prev[j - 1], c2);
}
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row[j + 1], label_row[j + 1], cost_row[j + 1], c1);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j + 1], label_row_prev[j + 1], cost_row_prev[j + 1], c2);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
}
}
#undef CHK_GD
}
void RICInterpolatorImpl::buildGraph(Mat& distances, Mat& cost_map)
{
float *dist_row, *cost_row;
float *dist_row_prev, *cost_row_prev;
const int *label_row;
const int *label_row_prev;
int i, j;
const float c1 = 1.0f / 2.0f;
const float c2 = sqrt(2.0f) / 2.0f;
float d;
bool found;
int h = labels.rows;
int w = labels.cols;
#define CHK_GD(cur_dist,cur_label,cur_cost,prev_dist,prev_label,prev_cost,coef)\
if(cur_label!=prev_label)\
{\
d = prev_dist + cur_dist + coef*(cur_cost+prev_cost);\
found = false;\
for(unsigned int n=0;n<g[prev_label].size();n++)\
{\
if(g[prev_label][n].label==cur_label)\
{\
g[prev_label][n].dist = min(g[prev_label][n].dist,d);\
found=true;\
break;\
}\
}\
if(!found)\
g[prev_label].push_back(node(cur_label ,d));\
}
dist_row = distances.ptr<float>(0);
label_row = labels.ptr<int>(0);
cost_row = cost_map.ptr<float>(0);
for (j = 1; j < w; j++)
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row[j - 1], label_row[j - 1], cost_row[j - 1], c1);
for (i = 1; i < h; i++)
{
dist_row = distances.ptr<float>(i);
dist_row_prev = distances.ptr<float>(i - 1);
label_row = labels.ptr<int>(i);
label_row_prev = labels.ptr<int>(i - 1);
cost_row = cost_map.ptr<float>(i);
cost_row_prev = cost_map.ptr<float>(i - 1);
j = 0;
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j + 1], label_row_prev[j + 1], cost_row_prev[j + 1], c2);
j++;
for (; j < w - 1; j++)
{
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row[j - 1], label_row[j - 1], cost_row[j - 1], c1);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j - 1], label_row_prev[j - 1], cost_row_prev[j - 1], c2);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j + 1], label_row_prev[j + 1], cost_row_prev[j + 1], c2);
}
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row[j - 1], label_row[j - 1], cost_row[j - 1], c1);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j - 1], label_row_prev[j - 1], cost_row_prev[j - 1], c2);
CHK_GD(dist_row[j], label_row[j], cost_row[j], dist_row_prev[j], label_row_prev[j], cost_row_prev[j], c1);
}
#undef CHK_GD
// force equal distances in both directions:
node* neighbors;
for (i = 0; i < match_num; i++)
{
if (g[i].empty())
continue;
neighbors = &g[i].front();
for (j = 0; j < (int)g[i].size(); j++)
{
found = false;
for (unsigned int n = 0; n < g[neighbors[j].label].size(); n++)
{
if (g[neighbors[j].label][n].label == i)
{
neighbors[j].dist = g[neighbors[j].label][n].dist = min(neighbors[j].dist, g[neighbors[j].label][n].dist);
found = true;
break;
}
}
if (!found)
g[neighbors[j].label].push_back(node((int)i, neighbors[j].dist));
}
}
}
int RICInterpolatorImpl::overSegmentaion(const Mat & img, Mat & outLabels, const int spSize)
{
Mat labImg;
cvtColor(img, labImg, COLOR_BGR2Lab);
Ptr< SuperpixelSLIC> slic = createSuperpixelSLIC(labImg, slic_type, spSize, sp_ruler);
slic->iterate(5);
slic->getLabels(outLabels);
return slic->getNumberOfSuperpixels();
}
void RICInterpolatorImpl::superpixelNeighborConstruction(const Mat & _labels, int labelCnt, Mat& outNeighbor)
{
// init
outNeighbor = Mat(labelCnt, max_neighbors, CV_32SC1); // only support 32 neighbors
outNeighbor.setTo(-1);
vector<int> diffPairs(labels.cols*_labels.rows * 4, 0);
int diffPairCnt = 0;
for (int i = 1; i < _labels.rows; i++) {
for (int j = 1; j < _labels.cols; j++) {
int l0 = _labels.at<int>(i,j);
int l1 = _labels.at<int>(i,j- 1);
int l2 = _labels.at<int>(i-1,j);
if (l0 != l1) {
diffPairs[2 * diffPairCnt] = l0;
diffPairs[2 * diffPairCnt + 1] = l1;
diffPairCnt++;
}
if (l0 != l2) {
diffPairs[2 * diffPairCnt] = l0;
diffPairs[2 * diffPairCnt + 1] = l2;
diffPairCnt++;
}
}
}
for (int i = 0; i < diffPairCnt; i++) {
int a = diffPairs[2 * i];
int b = diffPairs[2 * i + 1];
int k = 0;
// add to neighbor list of a
for (k = 0; k < max_neighbors; k++) {
if (outNeighbor.at<int>(a, k) < 0) {
break;
}
if (outNeighbor.at<int>(a,k) == b) {
k = -1;
break;
}
}
if (k >= 0 && k < max_neighbors) {
outNeighbor.at<int>(a, k) = b;
}
// add to neighbor list of b
for (k = 0; k < max_neighbors; k++) {
if (outNeighbor.at<int>(b, k) < 0) {
break;
}
if (outNeighbor.at<int>(b, k) == a) {
k = -1;
break;
}
}
if (k >= 0 && k < max_neighbors) {
outNeighbor.at<int>(b, k) = a;
}
}
}
void RICInterpolatorImpl::superpixelLayoutAnalysis(const Mat & _labels, int labelCnt, Mat & outCenterPositions, Mat & outNodeItemLists)
{
outCenterPositions = Mat(labelCnt,1,CV_32FC2); // x and y
outCenterPositions.setTo(0);
vector<int> itemCnt(labelCnt, 0);
for (int i = 0; i < _labels.rows; i++) {
for (int j = 0; j < _labels.cols; j++) {
int id = _labels.at<int>(i,j);
outCenterPositions.at<Point2f>(id) += Point2f(static_cast<float>(j),static_cast<float>(i));
itemCnt[id]++;
}
}
int maxItemCnt = 0;
for (int i = 0; i < labelCnt; i++) {
if (itemCnt[i] > maxItemCnt) {
maxItemCnt = itemCnt[i];
}
if (itemCnt[i] > 0) {
outCenterPositions.at<Point2f>(i).x /= itemCnt[i];
outCenterPositions.at<Point2f>(i).y /= itemCnt[i];
}
else {
outCenterPositions.at<Point2f>(i) = Point2f(-1,-1);
}
}
// get node item lists
outNodeItemLists = Mat(labelCnt, maxItemCnt, CV_32SC2);
outNodeItemLists.setTo(-1);
fill(itemCnt.begin(), itemCnt.end(), 0);
for (int i = 0; i < _labels.rows; i++) {
for (int j = 0; j < _labels.cols; j++) {
int id = _labels.at<int>(i,j);
int cnt = itemCnt[id];
outNodeItemLists.at<Point>(id, cnt) = Point(j,i);
itemCnt[id]++;
}
}
}
void RICInterpolatorImpl::findSupportMatches(vector<int> & srcIds, int srcCnt, int supportCnt, Mat & matNN,
Mat & matNNDis, vector<int> & outSupportIds, vector<float> & outSupportDis)
{
fill(outSupportIds.begin(), outSupportIds.end(), -1); // -1
fill(outSupportDis.begin(), outSupportDis.end(), -1.f); // -1
int allNodeCnt = matNN.rows;
MinHeap H(allNodeCnt); // min-heap
vector<float> currDis(allNodeCnt);
for (int i = 0; i < srcCnt; i++)
{
int id = srcIds[i];
int* pSupportIds = &outSupportIds[i * supportCnt];
float* pSupportDis = &outSupportDis[i * supportCnt];
H.Clear();
fill(currDis.begin(), currDis.end(), numeric_limits<float>::max());
int validSupportCnt = 0;
H.Push(static_cast<float>(id), 0); // min distance
currDis[id] = 0;
while (H.Size()) {
float dis;
int idx = static_cast<int>(H.Pop(&dis));
if (dis > currDis[idx]) {
continue;
}
pSupportIds[validSupportCnt] = idx;
pSupportDis[validSupportCnt] = dis;
validSupportCnt++;
if (validSupportCnt >= supportCnt) {
break;
}
for (int k = 0; k < matNN.cols; k++) {
int nb = matNN.at<int>(idx, k);
if (nb < 0) {
break;
}
float newDis = dis + matNNDis.at<float>(idx,k);
if (newDis < currDis[nb]) {
H.Push(static_cast<float>(nb), newDis);
currDis[nb] = newDis;
}
}
}
}
}
int RICInterpolatorImpl::PropagateModels(int spCnt, Mat & spNN, vector<int> & supportMatchIds, vector<float> & supportMatchDis, int supportCnt,
const vector<SparseMatch> &inputMatches, Mat & outModels)
{
int iterCnt = model_iter;
srand(0);
Mat inLierFlag(spCnt, supportCnt, CV_32SC1);
Mat tmpInlierFlag(1, supportCnt, CV_32SC1);
Mat tmpModel(1, 6, CV_32FC1);
// prepare data
vector<float> bestCost(spCnt);
parallel_for_(Range(0, spCnt), [&](const Range& range)
{
for (int i = range.start; i < range.end; i++)
{
Mat outModelRow = outModels.row(i);
Mat inlierFlagRow = inLierFlag.row(i);
bestCost[i] =
HypothesisEvaluation(
outModelRow,
&supportMatchIds[i * supportCnt],
&supportMatchDis[i * supportCnt],
supportCnt,
inputMatches,
inlierFlagRow);
}
}
);
parallel_for_(Range(0, iterCnt), [&](const Range& range)
{
vector<int> vFlags(spCnt);
for (int iter = range.start; iter < range.end; iter++)
{
fill(vFlags.begin(), vFlags.end(), 0);
int startPos = 0, endPos = spCnt, step = 1;
if (iter % 2 == 1) {
startPos = spCnt - 1; endPos = -1; step = -1;
}
for (int idx = startPos; idx != endPos; idx += step)
{
for (int i = 0; i < spNN.cols; i++) {
int nb = spNN.at<int>(idx, i);
if (nb < 0) break;
if (!vFlags[nb]) continue;
Mat NNModel = outModels.row(nb);
float cost = HypothesisEvaluation(
outModels.row(nb),
&supportMatchIds[idx * supportCnt],
&supportMatchDis[idx * supportCnt],
supportCnt,
inputMatches,
tmpInlierFlag);
if (cost < bestCost[idx])
{
outModels.row(nb).copyTo(outModels.row(idx));
tmpInlierFlag.copyTo(inLierFlag.row(idx));
bestCost[idx] = cost;
}
}
// random test
int testCnt = 1;
for (int i = 0; i < testCnt; i++) {
if (HypothesisGeneration(&supportMatchIds[idx * supportCnt], supportCnt, inputMatches, tmpModel) == 0)
{
float cost = HypothesisEvaluation(
tmpModel,
&supportMatchIds[idx * supportCnt],
&supportMatchDis[idx * supportCnt],
supportCnt,
inputMatches,
tmpInlierFlag);
if (cost < bestCost[idx])
{
tmpModel.copyTo(outModels.row(idx));
tmpInlierFlag.copyTo(inLierFlag.row(idx));
bestCost[idx] = cost;
}
}
}
vFlags[idx] = 1;
}
}
}
);
// refinement
if (refine_models)
{
parallel_for_(Range(0, spCnt), [&](const Range& range)
{
int averInlier = 0;
int minPtCnt = 30;
for (int i = range.start; i < range.end; i++)
{
Mat pt1(supportCnt, 1, CV_32FC2);
Mat pt2(supportCnt, 1, CV_32FC2);
vector<int> inlier_labels(supportCnt);
vector<float> inlier_distances(supportCnt);
Mat fitModel;
int* matNodes = &supportMatchIds[i * supportCnt];
float* matDis = &supportMatchDis[i * supportCnt];
int inlierCnt = 0;
for (int k = 0; k < supportCnt; k++) {
if (inLierFlag.at<int>(i, k))
{
int matId = matNodes[k];
inlier_labels[inlierCnt] = matId;
inlier_distances[inlierCnt] = GetWeightFromDistance(matDis[k]);
inlierCnt++;
}
}
if (inlierCnt >= minPtCnt)
{
weightedLeastSquaresAffineFit(&inlier_labels[0], &inlier_distances[0], inlierCnt, 0.01f, &inputMatches[0], fitModel);
fitModel.reshape(1, 1).copyTo(outModels.row(i));
}
averInlier += inlierCnt;
}
}
);
}
return 0;
}
float RICInterpolatorImpl::GetWeightFromDistance(float dis)
{
return exp(-dis / (alpha * 1000));
}
float RICInterpolatorImpl::HypothesisEvaluation(const Mat & inModel, const int * matNodes, const float * matDis, int matCnt, const vector<SparseMatch> & inputMatches, Mat & outInLier)
{
float errTh = 5.;
// find inliers
int inLierCnt = 0;
float cost = 0;
for (int k = 0; k < matCnt; k++) {
int matId = matNodes[k];
const SparseMatch & p = inputMatches[matId];
float x1 = p.reference_image_pos.x;
float y1 = p.reference_image_pos.y;
float xp = inModel.at<float>(0) * x1 + inModel.at<float>(1) * y1 + inModel.at<float>(2);
float yp = inModel.at<float>(3) * x1 + inModel.at<float>(4) * y1 + inModel.at<float>(5);
float pu = xp - x1, pv = yp - y1;
float tu = p.target_image_pos.x - p.reference_image_pos.x;
float tv = p.target_image_pos.y - p.reference_image_pos.y;
float wt = GetWeightFromDistance(matDis[k]);
if (std::isnan(pu) || std::isnan(pv)) {
outInLier.at<int>(k) = 0;
cost += wt * errTh;
continue;
}
float dis = sqrt((tu - pu)*(tu - pu) + (tv - pv)*(tv - pv));
if (dis < errTh) {
outInLier.at<int>(k) = 1;
inLierCnt++;
cost += wt * dis;
}
else {
outInLier.at<int>(k) = 0;
cost += wt * errTh;
}
}
return cost;
}
int RICInterpolatorImpl::HypothesisGeneration(int* matNodes, int matCnt, const vector<SparseMatch> & inputMatches, Mat & outModel)
{
if (matCnt < 3)
{
return -1;
}
int pickTimes = 0;
int maxPickTimes = 10;
float p1[6], p2[6]; // 3 pairs
bool pick_data = true;
float deter = 0;
while (pick_data)
{
pick_data = false;
// pick 3 group of points randomly
for (int k = 0; k < 3; k++) {
int matId = matNodes[rand() % matCnt];
const SparseMatch & p = inputMatches[matId];
p1[2 * k] = p.reference_image_pos.x;
p1[2 * k + 1] = p.reference_image_pos.y;
p2[2 * k] = p.target_image_pos.x;
p2[2 * k + 1] = p.target_image_pos.y;
}
// are the 3 points on the same line ?
deter = 0; // determinant
deter = p1[0] * p1[3] + p1[2] * p1[5] + p1[4] * p1[1]
- p1[4] * p1[3] - p1[0] * p1[5] - p1[2] * p1[1];
if (abs(deter) <= FLT_EPSILON)
{
pickTimes++;
if (pickTimes > maxPickTimes) {
return -1;
}
pick_data = true;
}
}
// estimate the model
float inv[9];
inv[0] = (p1[3] - p1[5]) / deter;
inv[1] = (p1[5] - p1[1]) / deter;
inv[2] = (p1[1] - p1[3]) / deter;
inv[3] = (p1[4] - p1[2]) / deter;
inv[4] = (p1[0] - p1[4]) / deter;
inv[5] = (p1[2] - p1[0]) / deter;
inv[6] = (p1[2] * p1[5] - p1[3] * p1[4]) / deter;
inv[7] = (p1[1] * p1[4] - p1[0] * p1[5]) / deter;
inv[8] = (p1[0] * p1[3] - p1[1] * p1[2]) / deter;
outModel.at<float>(0) = inv[0] * p2[0] + inv[1] * p2[2] + inv[2] * p2[4];
outModel.at<float>(1) = inv[3] * p2[0] + inv[4] * p2[2] + inv[5] * p2[4];
outModel.at<float>(2) = inv[6] * p2[0] + inv[7] * p2[2] + inv[8] * p2[4];
outModel.at<float>(3) = inv[0] * p2[1] + inv[1] * p2[3] + inv[2] * p2[5];
outModel.at<float>(4) = inv[3] * p2[1] + inv[4] * p2[3] + inv[5] * p2[5];
outModel.at<float>(5) = inv[6] * p2[1] + inv[7] * p2[3] + inv[8] * p2[5];
return 0;
}
CV_EXPORTS_W
Ptr<RICInterpolator> createRICInterpolator()
{
return Ptr<RICInterpolator>(RICInterpolatorImpl::create());
}
} }
} }
...@@ -95,6 +95,54 @@ TEST(InterpolatorTest, ReferenceAccuracy) ...@@ -95,6 +95,54 @@ TEST(InterpolatorTest, ReferenceAccuracy)
EXPECT_LE(cv::norm(res_flow, ref_flow, NORM_L1) , MAX_MEAN_DIF*res_flow.total()); EXPECT_LE(cv::norm(res_flow, ref_flow, NORM_L1) , MAX_MEAN_DIF*res_flow.total());
} }
TEST(InterpolatorTest, RICReferenceAccuracy)
{
double MAX_DIF = 6.0;
double MAX_MEAN_DIF = 60.0 / 256.0;
string dir = getDataDir() + "cv/sparse_match_interpolator";
Mat src = imread(getDataDir() + "cv/optflow/RubberWhale1.png", IMREAD_COLOR);
ASSERT_FALSE(src.empty());
Mat ref_flow = readOpticalFlow(dir + "/RubberWhale_reference_result.flo");
ASSERT_FALSE(ref_flow.empty());
Mat src1 = imread(getDataDir() + "cv/optflow/RubberWhale2.png", IMREAD_COLOR);
ASSERT_FALSE(src.empty());
std::ifstream file((dir + "/RubberWhale_sparse_matches.txt").c_str());
float from_x, from_y, to_x, to_y;
vector<Point2f> from_points;
vector<Point2f> to_points;
while (file >> from_x >> from_y >> to_x >> to_y)
{
from_points.push_back(Point2f(from_x, from_y));
to_points.push_back(Point2f(to_x, to_y));
}
Mat res_flow;
Ptr<RICInterpolator> interpolator = createRICInterpolator();
interpolator->setK(32);
interpolator->setSuperpixelSize(15);
interpolator->setSuperpixelNNCnt(150);
interpolator->setSuperpixelRuler(15.f);
interpolator->setSuperpixelMode(ximgproc::SLIC);
interpolator->setAlpha(0.7f);
interpolator->setModelIter(4);
interpolator->setRefineModels(true);
interpolator->setMaxFlow(250.f);
interpolator->setUseVariationalRefinement(true);
interpolator->setUseGlobalSmootherFilter(true);
interpolator->setFGSLambda(500.f);
interpolator->setFGSSigma(1.5f);
interpolator->interpolate(src, from_points, src1, to_points, res_flow);
EXPECT_LE(cv::norm(res_flow, ref_flow, NORM_INF), MAX_DIF);
EXPECT_LE(cv::norm(res_flow, ref_flow, NORM_L1), MAX_MEAN_DIF*res_flow.total());
}
TEST_P(InterpolatorTest, MultiThreadReproducibility) TEST_P(InterpolatorTest, MultiThreadReproducibility)
{ {
if (cv::getNumberOfCPUs() == 1) if (cv::getNumberOfCPUs() == 1)
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment