diff --git a/corelib/src/OdometryMono.cpp b/corelib/src/OdometryMono.cpp index 36e8612f67..e4434841b6 100644 --- a/corelib/src/OdometryMono.cpp +++ b/corelib/src/OdometryMono.cpp @@ -360,7 +360,11 @@ Transform OdometryMono::computeTransform(const SensorData & data, OdometryInfo * true, this->getIterations(), this->getPnPReprojError(), - 0, +#if CV_MAJOR_VERSION < 3 + 0, // min inliers +#else + 0.99, // confidence +#endif inliersV, this->getPnPFlags()); @@ -875,7 +879,11 @@ Transform OdometryMono::computeTransform(const SensorData & data, OdometryInfo * false, this->getIterations(), this->getPnPReprojError(), - 0, +#if CV_MAJOR_VERSION < 3 + 0, // min inliers +#else + 0.99, // confidence +#endif inliersPnP, this->getPnPFlags());