opencv/modules/3d/test/test_odometry.cpp

712 lines
22 KiB
C++
Raw Normal View History

Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
// This file is part of OpenCV project.
// It is subject to the license terms in the LICENSE file found in the top-level directory
// of this distribution and at http://opencv.org/license.html
#include "test_precomp.hpp"
namespace opencv_test { namespace {
static
void warpFrame(const Mat& image, const Mat& depth, const Mat& rvec, const Mat& tvec, const Mat& K,
Mat& warpedImage, Mat& warpedDepth)
{
CV_Assert(!image.empty());
CV_Assert(image.type() == CV_8UC1);
CV_Assert(depth.size() == image.size());
CV_Assert(depth.type() == CV_32FC1);
CV_Assert(!rvec.empty());
CV_Assert(rvec.total() == 3);
CV_Assert(rvec.type() == CV_64FC1);
CV_Assert(!tvec.empty());
CV_Assert(tvec.size() == Size(1, 3));
CV_Assert(tvec.type() == CV_64FC1);
warpedImage.create(image.size(), CV_8UC1);
warpedImage = Scalar(0);
warpedDepth.create(image.size(), CV_32FC1);
warpedDepth = Scalar(FLT_MAX);
Mat cloud;
depthTo3d(depth, K, cloud);
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
Mat cloud3, channels[4];
cv::split(cloud, channels);
std::vector<Mat> merged = { channels[0], channels[1], channels[2] };
cv::merge(merged, cloud3);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
Mat Rt = Mat::eye(4, 4, CV_64FC1);
{
Mat R, dst;
cv::Rodrigues(rvec, R);
dst = Rt(Rect(0,0,3,3));
R.copyTo(dst);
dst = Rt(Rect(3,0,1,3));
tvec.copyTo(dst);
}
Mat warpedCloud, warpedImagePoints;
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
perspectiveTransform(cloud3, warpedCloud, Rt);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
projectPoints(warpedCloud.reshape(3, 1), Mat(3,1,CV_32FC1, Scalar(0)), Mat(3,1,CV_32FC1, Scalar(0)), K, Mat(1,5,CV_32FC1, Scalar(0)), warpedImagePoints);
warpedImagePoints = warpedImagePoints.reshape(2, cloud.rows);
Rect r(0, 0, image.cols, image.rows);
for(int y = 0; y < cloud.rows; y++)
{
for(int x = 0; x < cloud.cols; x++)
{
Point p = warpedImagePoints.at<Point2f>(y,x);
if(r.contains(p))
{
float curDepth = warpedDepth.at<float>(p.y, p.x);
float newDepth = warpedCloud.at<Point3f>(y, x).z;
if(newDepth < curDepth && newDepth > 0)
{
warpedImage.at<uchar>(p.y, p.x) = image.at<uchar>(y,x);
warpedDepth.at<float>(p.y, p.x) = newDepth;
}
}
}
}
warpedDepth.setTo(std::numeric_limits<float>::quiet_NaN(), warpedDepth > 100);
}
static
void dilateFrame(Mat& image, Mat& depth)
{
CV_Assert(!image.empty());
CV_Assert(image.type() == CV_8UC1);
CV_Assert(!depth.empty());
CV_Assert(depth.type() == CV_32FC1);
CV_Assert(depth.size() == image.size());
Mat mask(image.size(), CV_8UC1, Scalar(255));
for(int y = 0; y < depth.rows; y++)
for(int x = 0; x < depth.cols; x++)
if(cvIsNaN(depth.at<float>(y,x)) || depth.at<float>(y,x) > 10 || depth.at<float>(y,x) <= FLT_EPSILON)
mask.at<uchar>(y,x) = 0;
image.setTo(255, ~mask);
Mat minImage;
erode(image, minImage, Mat());
image.setTo(0, ~mask);
Mat maxImage;
dilate(image, maxImage, Mat());
depth.setTo(FLT_MAX, ~mask);
Mat minDepth;
erode(depth, minDepth, Mat());
depth.setTo(0, ~mask);
Mat maxDepth;
dilate(depth, maxDepth, Mat());
Mat dilatedMask;
dilate(mask, dilatedMask, Mat(), Point(-1,-1), 1);
for(int y = 0; y < depth.rows; y++)
for(int x = 0; x < depth.cols; x++)
if(!mask.at<uchar>(y,x) && dilatedMask.at<uchar>(y,x))
{
image.at<uchar>(y,x) = static_cast<uchar>(0.5f * (static_cast<float>(minImage.at<uchar>(y,x)) +
static_cast<float>(maxImage.at<uchar>(y,x))));
depth.at<float>(y,x) = 0.5f * (minDepth.at<float>(y,x) + maxDepth.at<float>(y,x));
}
}
class OdometryTest
{
public:
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
OdometryTest(OdometryType _otype,
OdometryAlgoType _algtype,
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
double _maxError1,
double _maxError5,
double _idError = DBL_EPSILON) :
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
otype(_otype),
algtype(_algtype),
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
maxError1(_maxError1),
maxError5(_maxError5),
idError(_idError)
{ }
void readData(Mat& image, Mat& depth) const;
static Mat getCameraMatrix()
{
float fx = 525.0f, // default
fy = 525.0f,
cx = 319.5f,
cy = 239.5f;
Matx33f K(fx, 0, cx,
0, fy, cy,
0, 0, 1);
return Mat(K);
}
static void generateRandomTransformation(Mat& R, Mat& t);
void run();
void checkUMats();
void prepareFrameCheck();
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
OdometryType otype;
OdometryAlgoType algtype;
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
double maxError1;
double maxError5;
double idError;
};
void OdometryTest::readData(Mat& image, Mat& depth) const
{
std::string dataPath = cvtest::TS::ptr()->get_data_path();
std::string imageFilename = dataPath + "/cv/rgbd/rgb.png";
std::string depthFilename = dataPath + "/cv/rgbd/depth.png";
image = imread(imageFilename, 0);
depth = imread(depthFilename, -1);
if(image.empty())
{
FAIL() << "Image " << imageFilename.c_str() << " can not be read" << std::endl;
}
if(depth.empty())
{
2022-06-24 05:53:57 +08:00
FAIL() << "Depth " << depthFilename.c_str() << "can not be read" << std::endl;
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
}
CV_DbgAssert(image.type() == CV_8UC1);
CV_DbgAssert(depth.type() == CV_16UC1);
{
Mat depth_flt;
depth.convertTo(depth_flt, CV_32FC1, 1.f/5000.f);
depth_flt.setTo(std::numeric_limits<float>::quiet_NaN(), depth_flt < FLT_EPSILON);
depth = depth_flt;
}
}
void OdometryTest::generateRandomTransformation(Mat& rvec, Mat& tvec)
{
const float maxRotation = (float)(3.f / 180.f * CV_PI); //rad
const float maxTranslation = 0.02f; //m
RNG& rng = theRNG();
rvec.create(3, 1, CV_64FC1);
tvec.create(3, 1, CV_64FC1);
randu(rvec, Scalar(-1000), Scalar(1000));
normalize(rvec, rvec, rng.uniform(0.007f, maxRotation));
randu(tvec, Scalar(-1000), Scalar(1000));
normalize(tvec, tvec, rng.uniform(0.008f, maxTranslation));
}
void OdometryTest::checkUMats()
{
Mat K = getCameraMatrix();
Mat image, depth;
readData(image, depth);
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
OdometrySettings ods;
ods.setCameraMatrix(K);
Odometry odometry = Odometry(otype, ods, algtype);
OdometryFrame odf = odometry.createOdometryFrame(OdometryFrameStoreType::UMAT);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
Mat calcRt;
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
UMat uimage, udepth;
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
image.copyTo(uimage);
depth.copyTo(udepth);
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
odf.setImage(uimage);
odf.setDepth(udepth);
uimage.release();
udepth.release();
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
odometry.prepareFrame(odf);
bool isComputed = odometry.compute(odf, odf, calcRt);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
ASSERT_TRUE(isComputed);
double diff = cv::norm(calcRt, Mat::eye(4, 4, CV_64FC1));
if (diff > idError)
{
FAIL() << "Incorrect transformation between the same frame (not the identity matrix), diff = " << diff << std::endl;
}
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
}
void OdometryTest::run()
{
Mat K = getCameraMatrix();
Mat image, depth;
readData(image, depth);
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
OdometrySettings ods;
ods.setCameraMatrix(K);
Odometry odometry = Odometry(otype, ods, algtype);
OdometryFrame odf = odometry.createOdometryFrame();
odf.setImage(image);
odf.setDepth(depth);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
Mat calcRt;
// 1. Try to find Rt between the same frame (try masks also).
Mat mask(image.size(), CV_8UC1, Scalar(255));
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
odometry.prepareFrame(odf);
2022-02-08 23:14:32 +08:00
bool isComputed;
isComputed = odometry.compute(odf, odf, calcRt);
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
if(!isComputed)
{
FAIL() << "Can not find Rt between the same frame" << std::endl;
}
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
double ndiff = cv::norm(calcRt, Mat::eye(4,4,CV_64FC1));
2022-06-24 05:53:57 +08:00
if (ndiff > idError)
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
{
2022-06-24 05:53:57 +08:00
FAIL() << "Incorrect transformation between the same frame (not the identity matrix), diff = " << ndiff << std::endl;
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
}
// 2. Generate random rigid body motion in some ranges several times (iterCount).
// On each iteration an input frame is warped using generated transformation.
// Odometry is run on the following pair: the original frame and the warped one.
// Comparing a computed transformation with an applied one we compute 2 errors:
// better_1time_count - count of poses which error is less than ground truth pose,
// better_5times_count - count of poses which error is 5 times less than ground truth pose.
int iterCount = 100;
int better_1time_count = 0;
int better_5times_count = 0;
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
for (int iter = 0; iter < iterCount; iter++)
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
{
Mat rvec, tvec;
generateRandomTransformation(rvec, tvec);
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
2022-02-08 23:14:32 +08:00
Mat warpedImage, warpedDepth, scaledDepth;
warpFrame(image, scaledDepth, rvec, tvec, K, warpedImage, warpedDepth);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
dilateFrame(warpedImage, warpedDepth); // due to inaccuracy after warping
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
OdometryFrame odfSrc = odometry.createOdometryFrame();
OdometryFrame odfDst = odometry.createOdometryFrame();
2022-02-08 23:14:32 +08:00
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
odfSrc.setImage(image);
odfSrc.setDepth(depth);
odfDst.setImage(warpedImage);
odfDst.setDepth(warpedDepth);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
odometry.prepareFrames(odfSrc, odfDst);
isComputed = odometry.compute(odfSrc, odfDst, calcRt);
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
if (!isComputed)
2022-02-08 23:14:32 +08:00
{
CV_LOG_INFO(NULL, "Iter " << iter << "; Odometry compute returned false");
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
continue;
2022-02-08 23:14:32 +08:00
}
Mat calcR = calcRt(Rect(0, 0, 3, 3)), calcRvec;
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
cv::Rodrigues(calcR, calcRvec);
calcRvec = calcRvec.reshape(rvec.channels(), rvec.rows);
Mat calcTvec = calcRt(Rect(3,0,1,3));
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
if (cvtest::debugLevel >= 10)
{
imshow("image", image);
imshow("warpedImage", warpedImage);
Mat resultImage, resultDepth;
warpFrame(image, depth, calcRvec, calcTvec, K, resultImage, resultDepth);
imshow("resultImage", resultImage);
waitKey(100);
}
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
// compare rotation
double possibleError = algtype == OdometryAlgoType::COMMON ? 0.11f : 0.015f;
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
Affine3f src = Affine3f(Vec3f(rvec), Vec3f(tvec));
Affine3f res = Affine3f(Vec3f(calcRvec), Vec3f(calcTvec));
Affine3f src_inv = src.inv();
Affine3f diff = res * src_inv;
double rdiffnorm = cv::norm(diff.rvec());
double tdiffnorm = cv::norm(diff.translation());
if (rdiffnorm < possibleError && tdiffnorm < possibleError)
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
better_1time_count++;
if (5. * rdiffnorm < possibleError && 5 * tdiffnorm < possibleError)
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
better_5times_count++;
CV_LOG_INFO(NULL, "Iter " << iter);
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
CV_LOG_INFO(NULL, "rdiff: " << Vec3f(diff.rvec()) << "; rdiffnorm: " << rdiffnorm);
CV_LOG_INFO(NULL, "tdiff: " << Vec3f(diff.translation()) << "; tdiffnorm: " << tdiffnorm);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
CV_LOG_INFO(NULL, "better_1time_count " << better_1time_count << "; better_5time_count " << better_5times_count);
}
if(static_cast<double>(better_1time_count) < maxError1 * static_cast<double>(iterCount))
{
FAIL() << "Incorrect count of accurate poses [1st case]: "
<< static_cast<double>(better_1time_count) << " / "
<< maxError1 * static_cast<double>(iterCount) << std::endl;
}
if(static_cast<double>(better_5times_count) < maxError5 * static_cast<double>(iterCount))
{
FAIL() << "Incorrect count of accurate poses [2nd case]: "
<< static_cast<double>(better_5times_count) << " / "
<< maxError5 * static_cast<double>(iterCount) << std::endl;
}
}
void OdometryTest::prepareFrameCheck()
{
Mat K = getCameraMatrix();
Mat image, depth;
readData(image, depth);
OdometrySettings ods;
ods.setCameraMatrix(K);
Odometry odometry = Odometry(otype, ods, algtype);
OdometryFrame odf = odometry.createOdometryFrame();
odf.setImage(image);
odf.setDepth(depth);
odometry.prepareFrame(odf);
Mat points, mask;
odf.getPyramidAt(points, OdometryFramePyramidType::PYR_CLOUD, 0);
odf.getPyramidAt(mask, OdometryFramePyramidType::PYR_MASK, 0);
OdometryFrame todf = odometry.createOdometryFrame();
if (otype != OdometryType::DEPTH)
{
Mat img;
odf.getPyramidAt(img, OdometryFramePyramidType::PYR_IMAGE, 0);
todf.setPyramidLevel(1, OdometryFramePyramidType::PYR_IMAGE);
todf.setPyramidAt(img, OdometryFramePyramidType::PYR_IMAGE, 0);
}
todf.setPyramidLevel(1, OdometryFramePyramidType::PYR_CLOUD);
todf.setPyramidAt(points, OdometryFramePyramidType::PYR_CLOUD, 0);
todf.setPyramidLevel(1, OdometryFramePyramidType::PYR_MASK);
todf.setPyramidAt(mask, OdometryFramePyramidType::PYR_MASK, 0);
odometry.prepareFrame(todf);
}
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
/****************************************************************************************\
* Tests registrations *
\****************************************************************************************/
TEST(RGBD_Odometry_Rgbd, algorithmic)
{
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
OdometryTest test(OdometryType::RGB, OdometryAlgoType::COMMON, 0.99, 0.89);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
test.run();
}
TEST(RGBD_Odometry_ICP, algorithmic)
{
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
OdometryTest test(OdometryType::DEPTH, OdometryAlgoType::COMMON, 0.99, 0.99);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
test.run();
}
TEST(RGBD_Odometry_RgbdICP, algorithmic)
{
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
OdometryTest test(OdometryType::RGB_DEPTH, OdometryAlgoType::COMMON, 0.99, 0.99);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
test.run();
}
TEST(RGBD_Odometry_FastICP, algorithmic)
{
OdometryTest test(OdometryType::DEPTH, OdometryAlgoType::FAST, 0.99, 0.89, FLT_EPSILON);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
test.run();
}
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
TEST(RGBD_Odometry_Rgbd, UMats)
{
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
OdometryTest test(OdometryType::RGB, OdometryAlgoType::COMMON, 0.99, 0.89);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
test.checkUMats();
}
TEST(RGBD_Odometry_ICP, UMats)
{
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
OdometryTest test(OdometryType::DEPTH, OdometryAlgoType::COMMON, 0.99, 0.99);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
test.checkUMats();
}
TEST(RGBD_Odometry_RgbdICP, UMats)
{
Merge pull request #20755 from DumDereDum:new_odometry New odometry Pipeline * first intergation * tests run, but not pass * add previous version of sigma calc * add minor comment * strange fixes * fix fast ICP * test changes; fast icp still not work correctly * finaly, it works * algtype fix * change affine comparison * boolean return * fix bug with angle and cos * test pass correctly * fix for kinfu pipeline * add compute points normals * update for new odometry * change odometry_evaluation * odometry_evaluation works * change debug logs * minor changes * change depth setting in odometryFrame * fastICP works with 4num points * all odometries work with 4mun points * odometry full works on 4num points and normals * replace ICP with DEPTH; comments replacements * create prepareFrame; add docs for Odometry * change getPyramids() * delete extra code * add intrinsics; but dont works * bugfix with nan checking * add gpu impl * change createOdometryFrame func * remove old fastICP code * comments fix * add comments * minor fixes * other minor fixes * add channels assert * add impl for odometry settings * add pimpl to odometry * linux warning fix * linux warning fix 1 * linux warning fix 2 * linux error fix * linux warning fix 3 * linux warning fix 4 * linux error fix 2 * fix test warnings * python build fix * doxygen fix * docs fix * change normal tests for 4channel point * all Normal tests pass * plane works * add warp frame body * minor fix * warning fixes * try to fix * try to fix 1 * review fix * lvls fix * createOdometryFrame fix * add comment * const reference * OPENCV_3D_ prefix * const methods * –OdometryFramePyramidType ifx * add assert * precomp moved upper * delete types_c * add assert for get and set functions * minor fixes * remove core.hpp from header * ocl_run add * warning fix * delete extra comment * minor fix * setDepth fix * delete underscore * odometry settings fix * show debug image fix * build error fix * other minor fix * add const to signatures * fix * conflict fix * getter fix
2021-12-03 01:53:44 +08:00
OdometryTest test(OdometryType::RGB_DEPTH, OdometryAlgoType::COMMON, 0.99, 0.99);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
test.checkUMats();
}
TEST(RGBD_Odometry_FastICP, UMats)
{
OdometryTest test(OdometryType::DEPTH, OdometryAlgoType::FAST, 0.99, 0.89, FLT_EPSILON);
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
test.checkUMats();
}
TEST(RGBD_Odometry_Rgbd, prepareFrame)
{
OdometryTest test(OdometryType::RGB, OdometryAlgoType::COMMON, 0.99, 0.89);
test.prepareFrameCheck();
}
TEST(RGBD_Odometry_ICP, prepareFrame)
{
OdometryTest test(OdometryType::DEPTH, OdometryAlgoType::COMMON, 0.99, 0.99);
test.prepareFrameCheck();
}
TEST(RGBD_Odometry_RgbdICP, prepareFrame)
{
OdometryTest test(OdometryType::RGB_DEPTH, OdometryAlgoType::COMMON, 0.99, 0.99);
test.prepareFrameCheck();
}
TEST(RGBD_Odometry_FastICP, prepareFrame)
{
OdometryTest test(OdometryType::DEPTH, OdometryAlgoType::FAST, 0.99, 0.89, FLT_EPSILON);
test.prepareFrameCheck();
}
2022-06-30 05:51:07 +08:00
struct WarpFrameTest
{
WarpFrameTest() :
srcDepth(), srcRgb(), srcMask(),
dstDepth(), dstRgb(), dstMask(),
warpedDepth(), warpedRgb(), warpedMask()
{}
void run(bool needRgb, bool scaleDown, bool checkMask, bool identityTransform, int depthType, int imageType);
Mat srcDepth, srcRgb, srcMask;
Mat dstDepth, dstRgb, dstMask;
Mat warpedDepth, warpedRgb, warpedMask;
};
void WarpFrameTest::run(bool needRgb, bool scaleDown, bool checkMask, bool identityTransform, int depthType, int rgbType)
2022-06-27 07:24:39 +08:00
{
std::string dataPath = cvtest::TS::ptr()->get_data_path();
std::string srcDepthFilename = dataPath + "/cv/rgbd/depth.png";
2022-06-27 07:24:39 +08:00
std::string srcRgbFilename = dataPath + "/cv/rgbd/rgb.png";
// The depth was generated using the script at 3d/misc/python/warp_test.py
2022-06-27 07:24:39 +08:00
std::string warpedDepthFilename = dataPath + "/cv/rgbd/warpedDepth.png";
std::string warpedRgbFilename = dataPath + "/cv/rgbd/warpedRgb.png";
2022-06-27 07:24:39 +08:00
srcDepth = imread(srcDepthFilename, IMREAD_UNCHANGED);
ASSERT_FALSE(srcDepth.empty()) << "Depth " << srcDepthFilename.c_str() << "can not be read" << std::endl;
if (identityTransform)
{
2022-06-27 07:24:39 +08:00
warpedDepth = srcDepth;
}
2022-06-27 07:24:39 +08:00
else
{
2022-06-27 07:24:39 +08:00
warpedDepth = imread(warpedDepthFilename, IMREAD_UNCHANGED);
ASSERT_FALSE(warpedDepth.empty()) << "Depth " << warpedDepthFilename.c_str() << "can not be read" << std::endl;
}
2022-06-27 07:24:39 +08:00
ASSERT_TRUE(srcDepth.type() == CV_16UC1);
ASSERT_TRUE(warpedDepth.type() == CV_16UC1);
2022-06-30 05:51:07 +08:00
Mat epsSrc = srcDepth > 0, epsWarped = warpedDepth > 0;
const double depthFactor = 5000.0;
// scale float types only
double depthScaleCoeff = scaleDown ? ( depthType == CV_16U ? 1. : 1./depthFactor ) : 1.;
double transScaleCoeff = scaleDown ? ( depthType == CV_16U ? depthFactor : 1. ) : depthFactor;
Mat srcDepthCvt, warpedDepthCvt;
srcDepth.convertTo(srcDepthCvt, depthType, depthScaleCoeff);
srcDepth = srcDepthCvt;
warpedDepth.convertTo(warpedDepthCvt, depthType, depthScaleCoeff);
warpedDepth = warpedDepthCvt;
Scalar badVal;
switch (depthType)
{
case CV_16U:
badVal = 0;
break;
case CV_32F:
badVal = std::numeric_limits<float>::quiet_NaN();
break;
case CV_64F:
badVal = std::numeric_limits<double>::quiet_NaN();
break;
default:
CV_Error(Error::StsBadArg, "Unsupported depth data type");
}
srcDepth.setTo(badVal, ~epsSrc);
warpedDepth.setTo(badVal, ~epsWarped);
if (checkMask)
{
srcMask = epsSrc; warpedMask = epsWarped;
}
else
{
srcMask = Mat(); warpedMask = Mat();
}
2022-06-27 07:24:39 +08:00
if (needRgb)
{
2022-06-30 05:51:07 +08:00
srcRgb = imread(srcRgbFilename, rgbType == CV_8UC1 ? IMREAD_GRAYSCALE : IMREAD_COLOR);
2022-06-27 07:24:39 +08:00
ASSERT_FALSE(srcRgb.empty()) << "Image " << srcRgbFilename.c_str() << "can not be read" << std::endl;
if (identityTransform)
{
2022-06-30 05:51:07 +08:00
srcRgb.copyTo(warpedRgb, epsSrc);
2022-06-27 07:24:39 +08:00
}
else
{
2022-06-30 05:51:07 +08:00
warpedRgb = imread(warpedRgbFilename, rgbType == CV_8UC1 ? IMREAD_GRAYSCALE : IMREAD_COLOR);
2022-06-27 07:24:39 +08:00
ASSERT_FALSE (warpedRgb.empty()) << "Image " << warpedRgbFilename.c_str() << "can not be read" << std::endl;
}
2022-06-30 05:51:07 +08:00
if (rgbType == CV_8UC4)
{
Mat newSrcRgb, newWarpedRgb;
cvtColor(srcRgb, newSrcRgb, COLOR_RGB2RGBA);
srcRgb = newSrcRgb;
// let's keep alpha channel
std::vector<Mat> warpedRgbChannels;
split(warpedRgb, warpedRgbChannels);
warpedRgbChannels.push_back(epsWarped);
merge(warpedRgbChannels, newWarpedRgb);
warpedRgb = newWarpedRgb;
}
ASSERT_TRUE(srcRgb.type() == rgbType);
ASSERT_TRUE(warpedRgb.type() == rgbType);
2022-06-27 07:24:39 +08:00
}
else
{
srcRgb = Mat(); warpedRgb = Mat();
}
2022-06-30 05:51:07 +08:00
// test data used to generate warped depth and rgb
// the script used to generate is at TODO: here
double fx = 525.0, fy = 525.0,
cx = 319.5, cy = 239.5;
Matx33d K(fx, 0, cx,
0, fy, cy,
0, 0, 1);
2022-06-27 07:24:39 +08:00
cv::Affine3d rt;
2022-06-30 05:51:07 +08:00
cv::Vec3d tr(-0.04, 0.05, 0.6);
rt = identityTransform ? cv::Affine3d() : cv::Affine3d(cv::Vec3d(0.1, 0.2, 0.3), tr * transScaleCoeff);
2022-06-30 05:51:07 +08:00
warpFrame(srcDepth, srcRgb, srcMask, rt.matrix, K, dstDepth, dstRgb, dstMask);
}
2022-06-30 05:51:07 +08:00
TEST(RGBD_Odometry_WarpFrame, inputTypes)
{
// [depthType, rgbType]
std::array<int, 5*2> types =
{ CV_16U, CV_8UC3,
CV_32F, CV_8UC3,
CV_64F, CV_8UC3,
CV_32F, CV_8UC1,
CV_32F, CV_8UC4 };
const double shortl2diff = 233.983;
const double shortlidiff = 1;
const double floatl2diff = 0.03820836;
const double floatlidiff = 0.00020004;
for (int i = 0; i < 5; i++)
2022-06-27 07:24:39 +08:00
{
2022-06-30 05:51:07 +08:00
int depthType = types[i*2 + 0];
int rgbType = types[i*2 + 1];
WarpFrameTest w;
// scale down does not happen on CV_16U
// to avoid integer overflow
w.run(/* needRgb */ true, /* scaleDown*/ true,
/* checkMask */ true, /* identityTransform */ false, depthType, rgbType);
double rgbDiff = cv::norm(w.dstRgb, w.warpedRgb, NORM_L2);
double maskDiff = cv::norm(w.dstMask, w.warpedMask, NORM_L2);
2022-06-27 07:24:39 +08:00
2022-06-30 05:51:07 +08:00
EXPECT_EQ(0, maskDiff);
EXPECT_EQ(0, rgbDiff);
2022-06-30 05:51:07 +08:00
double l2diff = cv::norm(w.dstDepth, w.warpedDepth, NORM_L2, w.warpedMask);
double lidiff = cv::norm(w.dstDepth, w.warpedDepth, NORM_INF, w.warpedMask);
2022-06-30 05:51:07 +08:00
double l2threshold = depthType == CV_16U ? shortl2diff : floatl2diff;
double lithreshold = depthType == CV_16U ? shortlidiff : floatlidiff;
EXPECT_GE(l2threshold, l2diff);
EXPECT_GE(lithreshold, lidiff);
}
}
2022-06-27 07:24:39 +08:00
TEST(RGBD_Odometry_WarpFrame, identity)
{
2022-06-30 05:51:07 +08:00
WarpFrameTest w;
w.run(/* needRgb */ true, /* scaleDown*/ true, /* checkMask */ true, /* identityTransform */ true, CV_32F, CV_8UC3);
double rgbDiff = cv::norm(w.dstRgb, w.warpedRgb, NORM_L2);
double maskDiff = cv::norm(w.dstMask, w.warpedMask, NORM_L2);
ASSERT_EQ(0, rgbDiff);
ASSERT_EQ(0, maskDiff);
double depthDiff = cv::norm(w.dstDepth, w.warpedDepth, NORM_L2, w.dstMask);
ASSERT_GE(DBL_EPSILON, depthDiff);
2022-06-27 07:24:39 +08:00
}
TEST(RGBD_Odometry_WarpFrame, noRgb)
{
2022-06-30 05:51:07 +08:00
WarpFrameTest w;
w.run(/* needRgb */ false, /* scaleDown*/ true, /* checkMask */ true, /* identityTransform */ false, CV_32F, CV_8UC3);
double maskDiff = cv::norm(w.dstMask, w.warpedMask, NORM_L2);
ASSERT_EQ(0, maskDiff);
double l2diff = cv::norm(w.dstDepth, w.warpedDepth, NORM_L2, w.warpedMask);
double lidiff = cv::norm(w.dstDepth, w.warpedDepth, NORM_INF, w.warpedMask);
ASSERT_GE(0.03820836, l2diff);
ASSERT_GE(0.00020004, lidiff);
2022-06-27 07:24:39 +08:00
}
TEST(RGBD_Odometry_WarpFrame, nansAreMasked)
{
2022-06-30 05:51:07 +08:00
WarpFrameTest w;
w.run(/* needRgb */ true, /* scaleDown*/ true, /* checkMask */ false, /* identityTransform */ false, CV_32F, CV_8UC3);
double rgbDiff = cv::norm(w.dstRgb, w.warpedRgb, NORM_L2);
ASSERT_EQ(0, rgbDiff);
Mat goodVals = (w.warpedDepth == w.warpedDepth);
double l2diff = cv::norm(w.dstDepth, w.warpedDepth, NORM_L2, goodVals);
double lidiff = cv::norm(w.dstDepth, w.warpedDepth, NORM_INF, goodVals);
ASSERT_GE(0.03820836, l2diff);
ASSERT_GE(0.00020004, lidiff);
2022-06-27 07:24:39 +08:00
}
TEST(RGBD_Odometry_WarpFrame, bigScale)
{
2022-06-30 05:51:07 +08:00
WarpFrameTest w;
w.run(/* needRgb */ true, /* scaleDown*/ false, /* checkMask */ true, /* identityTransform */ false, CV_32F, CV_8UC3);
double rgbDiff = cv::norm(w.dstRgb, w.warpedRgb, NORM_L2);
double maskDiff = cv::norm(w.dstMask, w.warpedMask, NORM_L2);
ASSERT_EQ(0, maskDiff);
ASSERT_EQ(0, rgbDiff);
double l2diff = cv::norm(w.dstDepth, w.warpedDepth, NORM_L2, w.warpedMask);
double lidiff = cv::norm(w.dstDepth, w.warpedDepth, NORM_INF, w.warpedMask);
ASSERT_GE(191.026565, l2diff);
ASSERT_GE(0.99951172, lidiff);
2022-06-27 07:24:39 +08:00
}
Merge pull request #20013 from savuor:rgbd_to_3d Moving RGBD parts to 3d * files moved from rgbd module in contrib repo * header paths fixed * perf file added * lapack compilation fixed * Rodrigues fixed in tests * rgbd namespace removed * headers fixed * initial: rgbd files moved to 3d module * rgbd updated from latest contrib master; less file duplication * "std::" for sin(), cos(), etc. * KinFu family -> back to contrib * paths & namespaces * removed duplicates, file version updated * namespace kinfu removed from 3d module * forgot to move test_colored_kinfu.cpp to contrib * tests fixed: Params removed * kinfu namespace removed * it works without objc bindings * include headers fixed * tests: data paths fixed * headers moved to/from public API * Intr -> Matx33f in public API * from kinfu_frame.hpp to utils.hpp * submap: Intr -> Matx33f, HashTSDFVolume -> Volume; no extra headers * no RgbdFrame class, no Mat fields & arg -> InputArray & pImpl * get/setPyramidAt() instead of lots of methods * Mat -> InputArray, TMat * prepareFrameCache: refactored * FastICPOdometry: +truncate threshold, +depthFactor; Mat/UMat choose * Mat/UMat choose * minor stuff related to headers * (un)signed int warnings; compilation minor issues * minors: submap: pyramids -> OdometryFrame; tests fix; FastICP minor; CV_EXPORTS_W for kinfu_frame.hpp * FastICPOdometry: caching, rgbCameraMatrix * OdometryFrame: pyramid%s% -> pyramids[] * drop: rgbCameraMatrix from FastICP, RGB cache mode, makeColoredFrameFrom depth and all color-functions it calls * makeFrameFromDepth, buildPyramidPointsNormals -> from public to internal utils.hpp * minors * FastICPOdometry: caching updated, init fields * OdometryFrameImpl<UMat> fixed * matrix building fixed; minors * returning linemode back to contrib * params.pose is Mat now * precomp headers reorganized * minor fixes, header paths, extra header removed * minors: intrinsics -> utils.hpp; whitespaces; empty namespace; warning fixed * moving declarations from/to headers * internal headers reorganized (once again) * fix include * extra var fix * fix include, fix (un)singed warning * calibration.cpp: reverting back * headers fix * workaround to fix bindings * temporary removed wrappers * VolumeType -> VolumeParams * (temporarily) removing wrappers for Volume and VolumeParams * pyopencv_linemod -> contrib * try to fix test_rgbd.py * headers fixed * fixing wrappers for rgbd * fixing docs * fixing rgbdPlane * RgbdNormals wrapped * wrap Volume and VolumeParams, VolumeType from enum to int * DepthCleaner wrapped * header folder "rgbd" -> "3d" * fixing header path * VolumeParams referenced by Ptr to support Python wrappers * render...() fixed * Ptr<VolumeParams> fixed * makeVolume(... resolution -> [X, Y, Z]) * fixing static declaration * try to fix ios objc bindings * OdometryFrame::release...() removed * fix for Odometry algos not supporting UMats: prepareFrameCache<>() * preparePyramidMask(): fix to compile with TMat = UMat * fixing debug guards * removing references back; adding makeOdometryFrame() instead * fixing OpenCL ICP hanging (some threads exit before reaching the barrier -> the rest threads hang) * try to fix objc wrapper warnings; rerun builders * VolumeType -> VolumeKind * try to fix OCL bug * prints removed * indentation fixed * headers fixed * license fix * WillowGarage licence notion removed, since it's in OpenCV's COPYRIGHT already * KinFu license notion shortened * debugging code removed * include guards fixed * KinFu license left in contrib module * isValidDepth() moved to private header * indentation fix * indentation fix in src files * RgbdNormals rewritten to pImpl * minor * DepthCleaner removed due to low code quality, no depthScale provided, no depth images found to be successfully filtered; can be replaced by bilateral filtering * minors, indentation * no "private" in public headers * depthTo3d test moved from separate file * Normals: setDepth() is useless, removing it * RgbdPlane => findPlanes() * rescaleDepth(): minor * warpFrame: minor * minor TODO * all Odometries (except base abstract class) rewritten to pImpl * FastICPOdometry now supports maxRotation and maxTranslation * minor * Odometry's children: now checks are done in setters * get rid of protected members in Odometry class * get/set cameraMatrix, transformType, maxRot/Trans, iters, minGradients -> OdometryImpl * cameraMatrix: from double to float * matrix exponentiation: Eigen -> dual quaternions * Odometry evaluation fixed to reuse existing code * "small" macro fixed by undef * pixNorm is calculated on CPU only now (and then uploads on GPU) * test registration: no cvtest classes * test RgbdNormals and findPlanes(): no cvtest classes * test_rgbd.py: minor fix * tests for Odometry: no cvtest classes; UMat tests; logging fixed * more CV_OVERRIDE to overriden functions * fixing nondependent names to dependent * more to prev commit * forgotten fixes: overriden functions, (non)dependent names * FastICPOdometry: fix UMat support when OpenCL is off * try to fix compilation: missing namespaces * Odometry: static const-mimicking functions to internal constants * forgotten change to prev commit * more forgotten fixes * do not expose "submap.hpp" by default * in-class enums: give names, CamelCase, int=>enums; minors * namespaces, underscores, String * std::map is used by pose graph, adding it * compute()'s signature fixed, computeImpl()'s too * RgbdNormals: Mat -> InputArray * depth.hpp: Mat -> InputArray * cameraMatrix: Matx33f -> InputArray + default value + checks * "details" headers are not visible by default * TSDF tests: rearranging checks * cameraMatrix: no (realistic) default value * renderPointsNormals*(): no wrappers for them * debug: assert on empty frame in TSDF tests * debugging code for TSDF GPU * debug from integrate to raycast * no (non-zero) default camera matrix anymore * drop debugging code (does not help) * try to fix TSDF GPU: constant -> global const ptr
2021-08-22 21:18:45 +08:00
}} // namespace