From f316dde2e861dc5d9a40446ce47997ad279ccf6a Mon Sep 17 00:00:00 2001 From: Vincent Rabaud Date: Sun, 10 Apr 2016 20:24:49 +0200 Subject: [PATCH] fix compilation with OpenCV3 --- cells/cv_bp/opencv/cv_highgui.cpp | 16 ++- cells/cv_bp/opencv/cv_mat.cpp | 4 + cells/cv_bp/opencv/highgui_defines.cpp | 14 ++- cells/opencv/calib/CircleDrawer.cpp | 1 + cells/opencv/calib/DepthTo3d.cpp | 8 +- cells/opencv/calib/SubrectRectifier.cpp | 5 +- cells/opencv/calib/pose_drawing.cpp | 6 +- cells/opencv/features2d/CMakeLists.txt | 1 - .../opencv/features2d/DescriptorExtractor.cpp | 24 ++++- cells/opencv/features2d/FeatureDetector.cpp | 20 +++- cells/opencv/features2d/ORB.cpp | 34 ++++--- cells/opencv/features2d/interfaces.cpp | 98 ------------------- cells/opencv/features2d/interfaces.h | 51 +++++++++- cells/opencv/highgui/DoubleDrawer.cpp | 1 + cells/opencv/highgui/FPSDrawer.cpp | 1 + cells/opencv/highgui/imshow.cpp | 4 +- cells/opencv/rgbd/Cleaner.cpp | 22 +++-- cells/opencv/rgbd/ClusterDrawer.cpp | 4 + cells/opencv/rgbd/DepthSwapper.cpp | 4 + cells/opencv/rgbd/Normal.cpp | 17 +++- cells/opencv/rgbd/Odometry.cpp | 63 ++++++------ cells/opencv/rgbd/OnPlaneClusterer.cpp | 4 + cells/opencv/rgbd/Plane.cpp | 22 ++++- cells/opencv/rgbd/module.cpp | 21 ++-- test/cells/ImageGen.cpp | 4 + 25 files changed, 271 insertions(+), 178 deletions(-) delete mode 100644 cells/opencv/features2d/interfaces.cpp diff --git a/cells/cv_bp/opencv/cv_highgui.cpp b/cells/cv_bp/opencv/cv_highgui.cpp index 3edb550..9e87e77 100644 --- a/cells/cv_bp/opencv/cv_highgui.cpp +++ b/cells/cv_bp/opencv/cv_highgui.cpp @@ -3,8 +3,6 @@ #include #include -#include -#include #include #if CV_MAJOR_VERSION == 2 && CV_MINOR_VERSION == 4 && CV_SUBMINOR_VERSION < 10 #include @@ -13,12 +11,17 @@ namespace cv_backports { using cv::destroyWindow; using cv::imshow; using cv::namedWindow; + using cv::setMouseCallback; using cv::setWindowProperty; using cv::startWindowThread; using cv::waitKey; } #endif +#include +#include +#include + namespace bp = boost::python; namespace @@ -70,8 +73,13 @@ namespace opencv_wrappers VideoCapture_.def(bp::init<>()); VideoCapture_.def(bp::init()); VideoCapture_.def(bp::init()); +#if CV_MAJOR_VERSION == 3 + typedef bool(cv::VideoCapture::*open_1)(const cv::String&); + typedef bool(cv::VideoCapture::*open_2)(int); +#else typedef bool(cv::VideoCapture::*open_1)(const std::string&); typedef bool(cv::VideoCapture::*open_2)(int); +#endif VideoCapture_.def("open", open_1(&cv::VideoCapture::open)); VideoCapture_.def("open", open_2(&cv::VideoCapture::open)); VideoCapture_.def("isOpened", &cv::VideoCapture::isOpened); @@ -106,7 +114,11 @@ namespace opencv_wrappers wrap_video_writer(); //image windows +#if CV_MAJOR_VERSION == 3 + bp::def("imshow", static_cast(cv::imshow)); +#else bp::def("imshow", cv_backports::imshow); +#endif bp::def("waitKey", waitKey); bp::def("namedWindow", cv_backports::namedWindow); //CV_EXPORTS void setMouseCallback( const string& windowName, MouseCallback onMouse, void* param=0); diff --git a/cells/cv_bp/opencv/cv_mat.cpp b/cells/cv_bp/opencv/cv_mat.cpp index b981268..e3f8d85 100644 --- a/cells/cv_bp/opencv/cv_mat.cpp +++ b/cells/cv_bp/opencv/cv_mat.cpp @@ -308,7 +308,11 @@ namespace tostr(cv::Mat& m) { std::stringstream ss; +#if CV_MAJOR_VERSION == 3 + ss << cv::Formatter::get(cv::Formatter::FMT_PYTHON)->format(m); +#else cv::Formatter::get("python")->write(ss,m); +#endif return ss.str(); } inline cv::Mat diff --git a/cells/cv_bp/opencv/highgui_defines.cpp b/cells/cv_bp/opencv/highgui_defines.cpp index e36c0ac..d70faa4 100644 --- a/cells/cv_bp/opencv/highgui_defines.cpp +++ b/cells/cv_bp/opencv/highgui_defines.cpp @@ -120,13 +120,19 @@ namespace opencv_wrappers opencv.attr("CV_CAP_PROP_GAIN") = int(CV_CAP_PROP_GAIN); opencv.attr("CV_CAP_PROP_EXPOSURE") = int(CV_CAP_PROP_EXPOSURE); opencv.attr("CV_CAP_PROP_CONVERT_RGB") = int(CV_CAP_PROP_CONVERT_RGB); -#if CV_MAJOR_VERSION > 2 || (CV_MAJOR_VERSION == 2 && (CV_MINOR_VERSION > 4 || (CV_MINOR_VERSION == 4 && CV_SUBMINOR_VERSION > 10))) +#if CV_MAJOR_VERSION == 3 + opencv.attr("CV_CAP_PROP_WHITE_BALANCE_BLUE_U") = int(CV_CAP_PROP_WHITE_BALANCE_BLUE_U); +#elif CV_MAJOR_VERSION == 2 && (CV_MINOR_VERSION > 4 || (CV_MINOR_VERSION == 4 && CV_SUBMINOR_VERSION > 10)) opencv.attr("CV_CAP_PROP_WHITE_BALANCE_U") = int(CV_CAP_PROP_WHITE_BALANCE_U); #else opencv.attr("CV_CAP_PROP_WHITE_BALANCE_BLUE_U") = int(CV_CAP_PROP_WHITE_BALANCE_BLUE_U); #endif opencv.attr("CV_CAP_PROP_RECTIFICATION") = int(CV_CAP_PROP_RECTIFICATION); +#if CV_MAJOR_VERSION == 3 + opencv.attr("CV_CAP_PROP_MONOCHROME") = int(CV_CAP_PROP_MONOCHROME); +#else opencv.attr("CV_CAP_PROP_MONOCROME") = int(CV_CAP_PROP_MONOCROME); +#endif opencv.attr("CV_CAP_PROP_SHARPNESS") = int(CV_CAP_PROP_SHARPNESS); opencv.attr("CV_CAP_PROP_AUTO_EXPOSURE") = int(CV_CAP_PROP_AUTO_EXPOSURE); // user can adjust refernce level @@ -135,7 +141,9 @@ namespace opencv_wrappers opencv.attr("CV_CAP_PROP_TEMPERATURE") = int(CV_CAP_PROP_TEMPERATURE); opencv.attr("CV_CAP_PROP_TRIGGER") = int(CV_CAP_PROP_TRIGGER); opencv.attr("CV_CAP_PROP_TRIGGER_DELAY") = int(CV_CAP_PROP_TRIGGER_DELAY); -#if CV_MAJOR_VERSION > 2 || (CV_MAJOR_VERSION == 2 && (CV_MINOR_VERSION > 4 || (CV_MINOR_VERSION == 4 && CV_SUBMINOR_VERSION > 10))) +#if CV_MAJOR_VERSION == 3 + opencv.attr("CV_CAP_PROP_WHITE_BALANCE_RED_V") = int(CV_CAP_PROP_WHITE_BALANCE_RED_V); +#elif CV_MAJOR_VERSION > 2 || (CV_MAJOR_VERSION == 2 && (CV_MINOR_VERSION > 4 || (CV_MINOR_VERSION == 4 && CV_SUBMINOR_VERSION > 10))) opencv.attr("CV_CAP_PROP_WHITE_BALANCE_V") = int(CV_CAP_PROP_WHITE_BALANCE_V); #else opencv.attr("CV_CAP_PROP_WHITE_BALANCE_RED_V") = int(CV_CAP_PROP_WHITE_BALANCE_RED_V); @@ -166,8 +174,10 @@ namespace opencv_wrappers opencv.attr("CV_CAP_OPENNI_VGA_30HZ") = int(CV_CAP_OPENNI_VGA_30HZ); opencv.attr("CV_CAP_OPENNI_SXGA_15HZ") = int(CV_CAP_OPENNI_SXGA_15HZ); +#if CV_MAJOR_VERSION == 2 opencv.attr("CV_CAP_ANDROID_COLOR_FRAME") = int(CV_CAP_ANDROID_COLOR_FRAME); opencv.attr("CV_CAP_ANDROID_GREY_FRAME") = int(CV_CAP_ANDROID_GREY_FRAME); +#endif //opencv.attr("CV_CAP_ANDROID_YUV_FRAME") = int(CV_CAP_ANDROID_YUV_FRAME); } } diff --git a/cells/opencv/calib/CircleDrawer.cpp b/cells/opencv/calib/CircleDrawer.cpp index 5803cb9..a9f5d24 100644 --- a/cells/opencv/calib/CircleDrawer.cpp +++ b/cells/opencv/calib/CircleDrawer.cpp @@ -1,6 +1,7 @@ #include #include #include +#include using ecto::tendrils; diff --git a/cells/opencv/calib/DepthTo3d.cpp b/cells/opencv/calib/DepthTo3d.cpp index e810a7c..ac4fc19 100644 --- a/cells/opencv/calib/DepthTo3d.cpp +++ b/cells/opencv/calib/DepthTo3d.cpp @@ -41,7 +41,13 @@ #include #include +#if CV_MAJOR_VERSION == 2 #include +using namespace cv; +#else +#include +using namespace cv::rgbd; +#endif using ecto::tendrils; namespace calib @@ -71,7 +77,7 @@ namespace calib const cv::Mat &depth = inputs.get("depth"), &uv = inputs.get("points"); cv::Mat points3d; - cv::depthTo3dSparse(depth, K, uv, points3d); + depthTo3dSparse(depth, K, uv, points3d); outputs["points3d"] << points3d; diff --git a/cells/opencv/calib/SubrectRectifier.cpp b/cells/opencv/calib/SubrectRectifier.cpp index aedad12..c137d83 100644 --- a/cells/opencv/calib/SubrectRectifier.cpp +++ b/cells/opencv/calib/SubrectRectifier.cpp @@ -5,7 +5,10 @@ #include #include +#include + using namespace ecto; +using std::vector; namespace calib { struct SubrectRectifier @@ -64,7 +67,7 @@ struct SubrectRectifier if (R.rows == 0 || R.cols == 0 || T.rows == 0 || T.cols == 0) { - *output = cvCreateMat(*xsize_pixels, *ysize_pixels, image.type()); + *output = cv::Mat(*xsize_pixels, *ysize_pixels, image.type()); return 0; } diff --git a/cells/opencv/calib/pose_drawing.cpp b/cells/opencv/calib/pose_drawing.cpp index 984a036..afbac65 100644 --- a/cells/opencv/calib/pose_drawing.cpp +++ b/cells/opencv/calib/pose_drawing.cpp @@ -6,7 +6,11 @@ #include "calib.hpp" #include + using ecto::tendrils; +using std::string; +using std::vector; + namespace calib { struct PoseDrawer @@ -38,7 +42,7 @@ namespace calib line(drawImage, ip[0], ip[3], c[3]); string scaleText = boost::str(boost::format("scale %0.2f meters")%scale); int baseline = 0; - Size sz = getTextSize(scaleText, CV_FONT_HERSHEY_SIMPLEX, 1, 1, &baseline); + Size sz = cv::getTextSize(scaleText, CV_FONT_HERSHEY_SIMPLEX, 1, 1, &baseline); Point box_origin(10, drawImage.size().height - 10); rectangle(drawImage, box_origin + Point(0, 5), box_origin + Point(sz.width, -sz.height - 5), Scalar::all(0), -1); putText(drawImage, scaleText, box_origin, CV_FONT_HERSHEY_SIMPLEX, 1.0, c[0], 1, CV_AA, false); diff --git a/cells/opencv/features2d/CMakeLists.txt b/cells/opencv/features2d/CMakeLists.txt index 565ebb7..179ff40 100644 --- a/cells/opencv/features2d/CMakeLists.txt +++ b/cells/opencv/features2d/CMakeLists.txt @@ -4,7 +4,6 @@ ectomodule(features2d DESTINATION ecto_opencv/ecto_cells DescriptorExtractor.cpp DrawKeypoints.cpp FeatureDetector.cpp - interfaces.cpp KeypointsToMat.cpp LshMatcher.cpp MatchesToMat.cpp diff --git a/cells/opencv/features2d/DescriptorExtractor.cpp b/cells/opencv/features2d/DescriptorExtractor.cpp index 1f1b699..97b4e08 100644 --- a/cells/opencv/features2d/DescriptorExtractor.cpp +++ b/cells/opencv/features2d/DescriptorExtractor.cpp @@ -43,6 +43,10 @@ #include #include +#if CV_MAJOR_VERSION == 3 +#include +#endif + #include "interfaces.h" //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -82,9 +86,25 @@ struct EctoDescriptorExtractor void configure(const tendrils& params, const tendrils& inputs, const tendrils& outputs) { +#if CV_MAJOR_VERSION == 3 + switch(T) { + case SIFT: + descriptor_extractor_ = cv::xfeatures2d::SIFT::create(); + break; + case SURF: + descriptor_extractor_ = cv::xfeatures2d::SURF::create(); + break; + case ORB: + descriptor_extractor_ = cv::ORB::create(); + break; + case BRIEF: + descriptor_extractor_ = cv::xfeatures2d::BriefDescriptorExtractor::create(); + break; + } +#else descriptor_extractor_ = cv::DescriptorExtractor::create(descriptor_extractor_type_names[T]); - - read_tendrils_as_file_node(params, boost::bind(&cv::DescriptorExtractor::read, &(*descriptor_extractor_), _1)); +#endif + read_tendrils_as_file_node(params, *descriptor_extractor_); } int diff --git a/cells/opencv/features2d/FeatureDetector.cpp b/cells/opencv/features2d/FeatureDetector.cpp index 48744ad..80d7ebd 100644 --- a/cells/opencv/features2d/FeatureDetector.cpp +++ b/cells/opencv/features2d/FeatureDetector.cpp @@ -44,6 +44,10 @@ #include #include +#if CV_MAJOR_VERSION == 3 +#include +#endif + #include "interfaces.h" //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// @@ -83,9 +87,23 @@ struct EctoFeatureDetector void configure(const tendrils& params, const tendrils& inputs, const tendrils& outputs) { +#if CV_MAJOR_VERSION == 3 + switch(T) { + case FAST: + feature_detector_ = cv::FastFeatureDetector::create(); + break; + case ORB: + feature_detector_ = cv::ORB::create(); + break; + case SIFT: + feature_detector_ = cv::xfeatures2d::SIFT::create(); + break; + } +#else feature_detector_ = cv::FeatureDetector::create(feature_detector_type_names[T]); +#endif - read_tendrils_as_file_node(params, boost::bind(&cv::FeatureDetector::read, &(*feature_detector_), _1)); + read_tendrils_as_file_node(params, *feature_detector_); } int diff --git a/cells/opencv/features2d/ORB.cpp b/cells/opencv/features2d/ORB.cpp index 8fa6cd5..47e2f5d 100644 --- a/cells/opencv/features2d/ORB.cpp +++ b/cells/opencv/features2d/ORB.cpp @@ -11,11 +11,11 @@ struct ORB { static void - declare_params(tendrils& p) + declare_params(tendrils& params) { - p.declare("n_features", "The number of desired features", 1000); - p.declare("n_levels", "The number of scales", 3); - p.declare("scale_factor", "The factor between scales", 1.2); + params.declare(&ORB::n_features_, "n_features", "The number of keypoints to use", 1000); + params.declare(&ORB::n_levels_, "n_levels", "The number of levels to use for ORB", 3); + params.declare(&ORB::scale_factor_, "scale_factor", "The scale factor to use for ORB", 1.2); } static void @@ -29,14 +29,16 @@ struct ORB void configure(const tendrils& params, const tendrils& inputs, const tendrils& outputs) { -#if (CV_MAJOR_VERSION > 2) || ((CV_MAJOR_VERSION == 2) && (CV_MINOR_VERSION >= 4)) - orb_ = cv::ORB(params.get("n_features"), params.get("scale_factor"), params.get("n_levels")); +#if CV_MAJOR_VERSION ==3 + orb_ = cv::ORB::create(*n_features_, *scale_factor_, *n_levels_); +#elif (CV_MAJOR_VERSION == 2) && (CV_MINOR_VERSION >= 4) + orb = cv::Ptr(new cv::ORB(*n_features_, *scale_factor_, *n_levels_)); #else cv::ORB::CommonParams orb_params; orb_params.first_level_ = 0; - orb_params.n_levels_ = params.get("n_levels"); - orb_params.scale_factor_ = params.get("scale_factor"); - orb_ = cv::ORB(params.get("n_features"), orb_params); + orb_params.n_levels_ = *n_levels_; + orb_params.scale_factor_ = *scale_factor_; + orb_ = cv::Ptr(new cv::ORB(*n_features_, orb_params)); #endif } @@ -49,7 +51,11 @@ struct ORB inputs["image"] >> image; inputs["mask"] >> mask; cv::Mat desc; - orb_(image, mask, keypoints, desc, !keypoints.empty()); //use the provided keypoints if they were given. +#if CV_MAJOR_VERSION == 3 + orb_->detectAndCompute(image, mask, keypoints, desc, !keypoints.empty()); //use the provided keypoints if they were given. +#else + (*orb_)(image, mask, keypoints, desc, !keypoints.empty()); //use the provided keypoints if they were given. +#endif if (!mask.empty()) { //need to do keypoint validation as ORB is broken. @@ -80,7 +86,9 @@ struct ORB return ecto::OK; } - cv::ORB orb_; + ecto::spore n_features_, n_levels_; + ecto::spore scale_factor_; + cv::Ptr orb_; }; struct DescriptorAccumulator { @@ -136,7 +144,11 @@ struct ORBstats desc.pop_back(1); for (int i = 0, end = desc.rows; i < end; i++) { +#if CV_MAJOR_VERSION == 3 + size_t distance = cv::norm(desc_i, desc.row(i), cv::NORM_HAMMING); +#else size_t distance = cv::normHamming(desc_i.data, desc.row(i).data, desc.cols); +#endif distances[distance]++; } } diff --git a/cells/opencv/features2d/interfaces.cpp b/cells/opencv/features2d/interfaces.cpp deleted file mode 100644 index 8326c6b..0000000 --- a/cells/opencv/features2d/interfaces.cpp +++ /dev/null @@ -1,98 +0,0 @@ -/* - * Software License Agreement (BSD License) - * - * Copyright (c) 2011, Willow Garage, Inc. - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * * Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * * Redistributions in binary form must reproduce the above - * copyright notice, this list of conditions and the following - * disclaimer in the documentation and/or other materials provided - * with the distribution. - * * Neither the name of Willow Garage, Inc. nor the names of its - * contributors may be used to endorse or promote products derived - * from this software without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; - * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - */ - -#include - -#include -#include - -#include "interfaces.h" - -std::string -temporary_yml_file_name() -{ - std::string fname; - { - char buffer[L_tmpnam]; - char* p = std::tmpnam(buffer); - if (p != NULL) - { - fname = std::string(buffer) + ".yml"; - } - else - throw std::runtime_error("Could not create temporary filename!"); - } - return fname; -} - -//////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// - -void -read_tendrils_as_file_node(const ecto::tendrils & tendrils, boost::function function) -{ - // Get the file - std::string file_name = temporary_yml_file_name(); - - // Write the tendril's to it - { - cv::FileStorage fs(file_name, cv::FileStorage::WRITE); - BOOST_FOREACH (const ecto::tendrils::value_type &tendril_pair, tendrils) - { - std::string tendril_name = tendril_pair.first; - const ecto::tendril & tendril = *(tendril_pair.second); - std::string type_name = tendril.type_name(); - fs << tendril_name; - if (type_name == "int") - fs << tendril.get(); - else if (type_name == "float") - fs << tendril.get(); - else - { - std::string error_message = "Unsupported type: "; - error_message += type_name; - throw std::runtime_error(error_message); - } - } - } - - { - cv::FileStorage fs(file_name, cv::FileStorage::READ); - function(fs.root()); - } - - // Remove the temporary file - boost::filesystem::remove(file_name.c_str()); -} diff --git a/cells/opencv/features2d/interfaces.h b/cells/opencv/features2d/interfaces.h index 1d59e95..be66c49 100644 --- a/cells/opencv/features2d/interfaces.h +++ b/cells/opencv/features2d/interfaces.h @@ -2,6 +2,7 @@ * Software License Agreement (BSD License) * * Copyright (c) 2011, Willow Garage, Inc. + * Copyright (c) 2016, Google, Inc. * All rights reserved. * * Redistribution and use in source and binary forms, with or without @@ -42,13 +43,59 @@ #include #include +#include +#include + using ecto::tendrils; //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// +template void -read_tendrils_as_file_node(const ecto::tendrils & tendrils, boost::function function); +read_tendrils_as_file_node(const ecto::tendrils & tendrils, T obj) { + // Get the file + std::string file_name; + { + char buffer[L_tmpnam]; + char* p = std::tmpnam(buffer); + if (p != NULL) + { + file_name = std::string(buffer) + ".yml"; + } + else + throw std::runtime_error("Could not create temporary filename!"); + } + + // Write the tendril's to it + { + cv::FileStorage fs(file_name, cv::FileStorage::WRITE); + BOOST_FOREACH (const ecto::tendrils::value_type &tendril_pair, tendrils) + { + std::string tendril_name = tendril_pair.first; + const ecto::tendril & tendril = *(tendril_pair.second); + std::string type_name = tendril.type_name(); + fs << tendril_name; + if (type_name == "int") + fs << tendril.get(); + else if (type_name == "float") + fs << tendril.get(); + else + { + std::string error_message = "Unsupported type: "; + error_message += type_name; + throw std::runtime_error(error_message); + } + } + } + + { + cv::FileStorage fs(file_name, cv::FileStorage::READ); + obj.read(fs.root()); + } + + // Remove the temporary file + boost::filesystem::remove(file_name.c_str()); +} //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/cells/opencv/highgui/DoubleDrawer.cpp b/cells/opencv/highgui/DoubleDrawer.cpp index b8f58da..f9abbc4 100644 --- a/cells/opencv/highgui/DoubleDrawer.cpp +++ b/cells/opencv/highgui/DoubleDrawer.cpp @@ -1,6 +1,7 @@ #include #include +#include #include #include diff --git a/cells/opencv/highgui/FPSDrawer.cpp b/cells/opencv/highgui/FPSDrawer.cpp index 6baddb0..851387f 100644 --- a/cells/opencv/highgui/FPSDrawer.cpp +++ b/cells/opencv/highgui/FPSDrawer.cpp @@ -1,6 +1,7 @@ #include #include +#include #include #include diff --git a/cells/opencv/highgui/imshow.cpp b/cells/opencv/highgui/imshow.cpp index 69fedeb..ee7c713 100644 --- a/cells/opencv/highgui/imshow.cpp +++ b/cells/opencv/highgui/imshow.cpp @@ -6,8 +6,7 @@ #include #include -#ifdef CV_VERSION_EPOCH -#if CV_VERSION_EPOCH == 2 && CV_VERSION_MAJOR == 4 && CV_VERSION_MINOR < 10 +#if CV_MAJOR_VERSION == 2 && CV_MINOR_VERSION == 4 && CV_SUBMINOR_VERSION < 10 #include #else namespace cv_backports { @@ -19,7 +18,6 @@ namespace cv_backports { using cv::waitKey; } #endif -#endif #include #include diff --git a/cells/opencv/rgbd/Cleaner.cpp b/cells/opencv/rgbd/Cleaner.cpp index a0f861d..91484e9 100644 --- a/cells/opencv/rgbd/Cleaner.cpp +++ b/cells/opencv/rgbd/Cleaner.cpp @@ -35,43 +35,49 @@ #include #include +#if CV_MAJOR_VERSION == 3 +#include +using cv::rgbd::DepthCleaner; +#else #include +using cv::DepthCleaner; +#endif using ecto::tendrils; namespace rgbd { //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// - struct DepthCleaner + struct DepthCleanerCell { static void declare_params(tendrils & params) { - params.declare(&DepthCleaner::method_, "method", "Conversion type.", cv::DepthCleaner::DEPTH_CLEANER_NIL); + params.declare(&DepthCleanerCell::method_, "method", "Conversion type.", DepthCleaner::DEPTH_CLEANER_NIL); } static void declare_io(const tendrils& params, tendrils& inputs, tendrils& outputs) { - inputs.declare(&DepthCleaner::image_in_, "image", "The depth map").required(true); + inputs.declare(&DepthCleanerCell::image_in_, "image", "The depth map").required(true); - outputs.declare(&DepthCleaner::image_out_, "image", "The cleaned up depth image"); + outputs.declare(&DepthCleanerCell::image_out_, "image", "The cleaned up depth image"); } int process(const tendrils& inputs, const tendrils& outputs) { if (depth_cleaner_.empty()) { - depth_cleaner_ = new cv::DepthCleaner(image_in_->depth(), 5, *method_); + depth_cleaner_ = new DepthCleaner(image_in_->depth(), 5, *method_); } (*depth_cleaner_)(*image_in_, *image_out_); return ecto::OK; } - cv::Ptr depth_cleaner_; + cv::Ptr depth_cleaner_; ecto::spore image_in_, image_out_; - ecto::spore method_; + ecto::spore method_; }; } -ECTO_CELL(rgbd, rgbd::DepthCleaner, "DepthCleaner", "Clean the depth map") +ECTO_CELL(rgbd, rgbd::DepthCleanerCell, "DepthCleaner", "Clean the depth map") diff --git a/cells/opencv/rgbd/ClusterDrawer.cpp b/cells/opencv/rgbd/ClusterDrawer.cpp index a6d8e80..c934dd6 100644 --- a/cells/opencv/rgbd/ClusterDrawer.cpp +++ b/cells/opencv/rgbd/ClusterDrawer.cpp @@ -40,7 +40,11 @@ #include #include +#if CV_MAJOR_VERSION == 3 +#include +#else #include +#endif #include diff --git a/cells/opencv/rgbd/DepthSwapper.cpp b/cells/opencv/rgbd/DepthSwapper.cpp index f56a8df..c11f43c 100644 --- a/cells/opencv/rgbd/DepthSwapper.cpp +++ b/cells/opencv/rgbd/DepthSwapper.cpp @@ -35,7 +35,11 @@ #include #include +#if CV_MAJOR_VERSION == 3 +#include +#else #include +#endif using ecto::tendrils; namespace rgbd diff --git a/cells/opencv/rgbd/Normal.cpp b/cells/opencv/rgbd/Normal.cpp index 02aa997..2dba89b 100644 --- a/cells/opencv/rgbd/Normal.cpp +++ b/cells/opencv/rgbd/Normal.cpp @@ -35,7 +35,14 @@ #include #include +#include +#if CV_MAJOR_VERSION == 3 +#include +using cv::rgbd::RgbdNormals; +#else #include +using cv::RgbdNormals; +#endif using ecto::tendrils; namespace rgbd @@ -47,7 +54,7 @@ namespace rgbd static void declare_params(tendrils & params) { - params.declare(&ComputeNormals::method_, "method", "Conversion type.", cv::RgbdNormals::RGBD_NORMALS_METHOD_FALS); + params.declare(&ComputeNormals::method_, "method", "Conversion type.", RgbdNormals::RGBD_NORMALS_METHOD_FALS); params.declare(&ComputeNormals::window_size_, "window_size", "The window size for smoothing.", 5); } @@ -65,19 +72,19 @@ namespace rgbd { if (normals_computer_.empty()) { if ((points3d_->depth() == CV_32F) || (points3d_->depth() == CV_64F)) - normals_computer_ = new cv::RgbdNormals(points3d_->rows, points3d_->cols, points3d_->depth(), *K_, + normals_computer_ = new RgbdNormals(points3d_->rows, points3d_->cols, points3d_->depth(), *K_, *window_size_, *method_); else - normals_computer_ = new cv::RgbdNormals(points3d_->rows, points3d_->cols, CV_32F, *K_, + normals_computer_ = new RgbdNormals(points3d_->rows, points3d_->cols, CV_32F, *K_, *window_size_, *method_); } (*normals_computer_)(*points3d_, *normals_); return ecto::OK; } - cv::Ptr normals_computer_; + cv::Ptr normals_computer_; ecto::spore points3d_, normals_, K_, depth_; - ecto::spore method_; + ecto::spore method_; ecto::spore window_size_; }; diff --git a/cells/opencv/rgbd/Odometry.cpp b/cells/opencv/rgbd/Odometry.cpp index aff9391..76dc1c6 100644 --- a/cells/opencv/rgbd/Odometry.cpp +++ b/cells/opencv/rgbd/Odometry.cpp @@ -36,19 +36,29 @@ #include #include #include +#include +#if CV_MAJOR_VERSION == 3 +#include +using cv::rgbd::RgbdOdometry; +using cv::rgbd::rescaleDepth; +using cv::rgbd::warpFrame; +#else #include #include +using cv::RgbdOdometry; +using cv::rescaleDepth; +using cv::warpFrame; +#endif #include #include +#include using ecto::tendrils; using namespace cv; using namespace std; -namespace rgbd -{ - struct Odometry + struct OdometryCell { static void declare_params(tendrils& params) @@ -60,13 +70,13 @@ namespace rgbd static void declare_io(const tendrils& params, tendrils& inputs, tendrils& outputs) { - inputs.declare(&Odometry::current_image_, "image", "The current visual frame.").required(true); - inputs.declare(&Odometry::current_depth_, "depth", "The current depth frame.").required(true); - inputs.declare(&Odometry::K_, "K", "The camera intrinsic parameter matrix.").required(true); + inputs.declare(&OdometryCell::current_image_, "image", "The current visual frame.").required(true); + inputs.declare(&OdometryCell::current_depth_, "depth", "The current depth frame.").required(true); + inputs.declare(&OdometryCell::K_, "K", "The camera intrinsic parameter matrix.").required(true); - outputs.declare(&Odometry::R_, "R", "The rotation of the camera pose with respect to the previous frame."); - outputs.declare(&Odometry::T_, "T", "The rotation of the camera pose with respect to the previous frame."); - outputs.declare(&Odometry::warp_, "image", "The warped previous image."); + outputs.declare(&OdometryCell::R_, "R", "The rotation of the camera pose with respect to the previous frame."); + outputs.declare(&OdometryCell::T_, "T", "The rotation of the camera pose with respect to the previous frame."); + outputs.declare(&OdometryCell::warp_, "image", "The warped previous image."); } void configure(const tendrils& params, const tendrils& inputs, const tendrils& outputs) @@ -109,34 +119,35 @@ namespace rgbd return ecto::OK; } - cv::TickMeter tm; cv::Mat Rt; cv::Mat cameraMatrix; K_->convertTo(cameraMatrix, CV_32FC1); - - if (odometry.empty()) + + if (odometry_.empty()) { - odometry = Algorithm::create("RGBD.RgbdOdometry"); - odometry->set("cameraMatrix", cameraMatrix); + odometry_.reset(new RgbdOdometry()); +#if CV_VERSION_MAJOR == 3 + odometry_->setCameraMatrix(cameraMatrix); +#else + odometry_->set("cameraMatrix", cameraMatrix); +#endif } - - if (odometry.empty()) + + if (odometry_.empty()) { std::cout << "Odometry algorithm can not be created." << std::endl; return -1; } - - tm.start(); bool isFound; bool compare_to_first = false; if (compare_to_first) - isFound = odometry->compute(first_image_gray_, first_depth_meters_, cv::Mat(), + isFound = odometry_->compute(first_image_gray_, first_depth_meters_, cv::Mat(), current_image_gray, current_depth_meters, cv::Mat(), Rt); else - isFound = odometry->compute(previous_image_gray_, previous_depth_meters_, cv::Mat(), + isFound = odometry_->compute(previous_image_gray_, previous_depth_meters_, cv::Mat(), current_image_gray, current_depth_meters, cv::Mat(), Rt); if (isFound) { @@ -146,11 +157,6 @@ namespace rgbd previous_pose_ = cv::Mat_(Rt) * previous_pose_; } - tm.stop(); - - //std::cout << "Rt = " << Rt << std::endl; - std::cout << "Time = " << tm.getTimeSec() << " sec." << std::endl; - if (!isFound) { std::cout << "Rigid body motion cann't be estimated for given RGBD data." << std::endl; @@ -164,7 +170,7 @@ namespace rgbd const Mat distCoeff(1, 5, CV_32FC1, Scalar(0)); std::cout << previous_pose_ << std::endl; - cv::warpFrame(first_image_, first_depth_meters_, cv::Mat(), previous_pose_, cameraMatrix, distCoeff, + warpFrame(first_image_, first_depth_meters_, cv::Mat(), previous_pose_, cameraMatrix, distCoeff, warpedImage0); warpedImage0.copyTo(*warp_); } @@ -187,7 +193,7 @@ namespace rgbd cv::Mat previous_image_; cv::Mat previous_depth_meters_; cv::Mat_ previous_pose_; - Ptr odometry; + cv::Ptr odometry_; ecto::spore warp_; /** The output rotation matrix */ @@ -195,6 +201,5 @@ namespace rgbd /** The output translation matrix */ ecto::spore T_; }; -} -ECTO_CELL(rgbd, rgbd::Odometry, "Odometry", "Uses the RGBDOdometry to figure out where the camera is.") +ECTO_CELL(rgbd, OdometryCell, "Odometry", "Uses the RGBDOdometry to figure out where the camera is.") diff --git a/cells/opencv/rgbd/OnPlaneClusterer.cpp b/cells/opencv/rgbd/OnPlaneClusterer.cpp index 0f087de..f3f96a9 100644 --- a/cells/opencv/rgbd/OnPlaneClusterer.cpp +++ b/cells/opencv/rgbd/OnPlaneClusterer.cpp @@ -39,7 +39,11 @@ #include #include +#if CV_MAJOR_VERSION == 3 +#include +#else #include +#endif #include diff --git a/cells/opencv/rgbd/Plane.cpp b/cells/opencv/rgbd/Plane.cpp index b24423a..ceb8501 100644 --- a/cells/opencv/rgbd/Plane.cpp +++ b/cells/opencv/rgbd/Plane.cpp @@ -41,7 +41,15 @@ #include #include +#if CV_MAJOR_VERSION == 3 +#include +using cv::rgbd::RgbdNormals; +using cv::rgbd::RgbdPlane; +#else #include +using cv::RgbdNormals; +using cv::RgbdPlane; +#endif #include @@ -68,7 +76,7 @@ namespace rgbd "c coefficient of the quadratic sensor error err=a*z^2+b*z+c. 0.0 fo Kinect.", 0.0); params.declare(&PlaneFinder::window_size_, "window_size", "The window size for smoothing.", 5); params.declare(&PlaneFinder::normal_method_, "normal_method", "The window size for smoothing.", - cv::RgbdNormals::RGBD_NORMALS_METHOD_FALS); + RgbdNormals::RGBD_NORMALS_METHOD_FALS); params.declare(&PlaneFinder::min_size_, "min_size", "The smallest size in pixels of a plane.", 0); } @@ -95,18 +103,22 @@ namespace rgbd if (normals_->empty()) { if (normals_computer_.empty()) - normals_computer_ = new cv::RgbdNormals(points3d_->rows, points3d_->cols, points3d_->depth(), *K_, + normals_computer_ = new RgbdNormals(points3d_->rows, points3d_->cols, points3d_->depth(), *K_, *window_size_, *normal_method_); (*normals_computer_)(*points3d_, *normals_); } if (plane_computer_.empty()) { +#if CV_MAJOR_VERSION == 3 + plane_computer_.reset(new RgbdPlane()); +#else plane_computer_ = cv::Algorithm::create("RGBD.RgbdPlane"); plane_computer_->set("sensor_error_a", *sensor_error_a_); plane_computer_->set("sensor_error_b", *sensor_error_b_); plane_computer_->set("sensor_error_c", *sensor_error_c_); plane_computer_->set("min_size", *min_size_); +#endif } (*plane_computer_)(*points3d_, *normals_, *masks_, *planes_); @@ -114,8 +126,8 @@ namespace rgbd } private: - cv::Ptr normals_computer_; - cv::Ptr plane_computer_; + cv::Ptr normals_computer_; + cv::Ptr plane_computer_; /** If true, display some result */ ecto::spore threshold_; @@ -139,7 +151,7 @@ namespace rgbd ecto::spore window_size_; - ecto::spore normal_method_; + ecto::spore normal_method_; }; //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////// diff --git a/cells/opencv/rgbd/module.cpp b/cells/opencv/rgbd/module.cpp index 99c555b..85bc02b 100644 --- a/cells/opencv/rgbd/module.cpp +++ b/cells/opencv/rgbd/module.cpp @@ -1,16 +1,25 @@ #include #include +#include +#if CV_MAJOR_VERSION == 3 +#include +using cv::rgbd::RgbdNormals; +using cv::rgbd::DepthCleaner; +#else #include +using cv::RgbdNormals; +using cv::DepthCleaner; +#endif namespace bp = boost::python; ECTO_DEFINE_MODULE(rgbd) { - bp::enum_("RgbdNormalsTypes").value("SRI", - cv::RgbdNormals::RGBD_NORMALS_METHOD_SRI).value( - "FALS", cv::RgbdNormals::RGBD_NORMALS_METHOD_FALS).value( - "LINEMOD", cv::RgbdNormals::RGBD_NORMALS_METHOD_LINEMOD); - bp::enum_("DepthCleanerTypes").value("NIL", - cv::DepthCleaner::DEPTH_CLEANER_NIL); + bp::enum_("RgbdNormalsTypes").value("SRI", + RgbdNormals::RGBD_NORMALS_METHOD_SRI).value( + "FALS", RgbdNormals::RGBD_NORMALS_METHOD_FALS).value( + "LINEMOD", RgbdNormals::RGBD_NORMALS_METHOD_LINEMOD); + bp::enum_("DepthCleanerTypes").value("NIL", + DepthCleaner::DEPTH_CLEANER_NIL); } diff --git a/test/cells/ImageGen.cpp b/test/cells/ImageGen.cpp index aa6cf43..3f06b28 100644 --- a/test/cells/ImageGen.cpp +++ b/test/cells/ImageGen.cpp @@ -3,7 +3,11 @@ #include #include #define SHOW() std::cout << __PRETTY_FUNCTION__ << std::endl; +#if CV_MAJOR_VERSION +#define REFCOUNT(X) std::cout << "ref count:" << ((X->u) ? (X->u->refcount) : 0) << std::endl; +#else #define REFCOUNT(X) std::cout << "ref count:" << ((X->refcount) ? *(X->refcount) : 0) << std::endl; +#endif using ecto::tendrils; namespace opencv_test