diff --git a/modules/python/bindings/include/mbt.hpp b/modules/python/bindings/include/mbt.hpp index 9095237ff8..b3cd321b4a 100644 --- a/modules/python/bindings/include/mbt.hpp +++ b/modules/python/bindings/include/mbt.hpp @@ -13,7 +13,7 @@ void bindings_vpMbGenericTracker(py::class_ &py pyMbGenericTracker.def("track", [](vpMbGenericTracker &self, std::map *> &mapOfImages, std::map> &mapOfPointClouds) { std::map mapOfWidths, mapOfHeights; - std::map> mapOfVectors; + std::map mapOfVectors; double t = vpTime::measureTimeMs(); for (const auto &point_cloud_pair: mapOfPointClouds) { @@ -27,20 +27,12 @@ void bindings_vpMbGenericTracker(py::class_ &py const auto shape = buffer.shape; mapOfHeights[point_cloud_pair.first] = shape[0]; mapOfWidths[point_cloud_pair.first] = shape[1]; - - std::vector pc(shape[0] * shape[1], vpColVector(3)); + vpMatrix pc(shape[0] * shape[1], 3); const double *data = point_cloud_pair.second.unchecked<3>().data(0, 0, 0); - for (ssize_t i = 0; i < shape[0]; ++i) { - for (ssize_t j = 0; j < shape[1]; ++j) { - size_t vec_idx = i * shape[1] + j; - size_t idx = i * shape[1] * 3 + j * 3; - memcpy(pc[vec_idx].data, data + idx, sizeof(double) * 3); - } - } - + memcpy(pc.data, data, shape[0] * shape[1] * 3 * sizeof(double)); mapOfVectors[point_cloud_pair.first] = std::move(pc); } - std::map * > mapOfVectorPtrs; + std::map mapOfVectorPtrs; for (const auto &p: mapOfVectors) { mapOfVectorPtrs[p.first] = &(p.second); } diff --git a/modules/python/config/imgproc.json b/modules/python/config/imgproc.json index 294b0d30ac..307aae2e31 100644 --- a/modules/python/config/imgproc.json +++ b/modules/python/config/imgproc.json @@ -3,5 +3,24 @@ "ignored_classes": [], "user_defined_headers": [], "classes": {}, + "functions": [ + { + "static": false, + "signature": "void findContours(const vpImage&, vp::vpContour&, std::vector>&, const vp::vpContourRetrievalType&)", + "use_default_param_policy": false, + "param_is_input": [ + true, + true, + false, + true + ], + "param_is_output": [ + false, + false, + true, + false + ] + } + ], "enums": {} } diff --git a/modules/python/config/klt.json b/modules/python/config/klt.json index efe99d00ae..ade21dbade 100644 --- a/modules/python/config/klt.json +++ b/modules/python/config/klt.json @@ -9,6 +9,23 @@ "static": false, "signature": "void display(const vpImage&, const vpColor&, unsigned int)", "custom_name": "displaySelf" + }, + { + "static": false, + "signature": "void getFeature(const int&, long&, float&, float&)", + "use_default_param_policy": false, + "param_is_input": [ + true, + false, + false, + false + ], + "param_is_output": [ + false, + true, + true, + true + ] } ] } diff --git a/modules/python/examples/synthetic_data_mbt.py b/modules/python/examples/synthetic_data_mbt.py index 0a82ecdc87..367a070d9b 100644 --- a/modules/python/examples/synthetic_data_mbt.py +++ b/modules/python/examples/synthetic_data_mbt.py @@ -72,6 +72,7 @@ def read_data(exp_config: MBTConfig, cam_depth: CameraParameters | None, I: Imag use_depth = cam_depth is not None iteration = 1 while True: + start_parse_time = time.time() color_filepath = exp_config.color_images_dir / color_format.format(iteration) if not color_filepath.exists(): print(f'Could not find image {color_filepath}, is the sequence finished?') @@ -82,12 +83,14 @@ def read_data(exp_config: MBTConfig, cam_depth: CameraParameters | None, I: Imag I_depth_raw = None point_cloud = None if use_depth: + t = time.time() depth_filepath = exp_config.depth_images_dir / depth_format.format(iteration) if not depth_filepath.exists(): print(f'Could not find image {depth_filepath}') return I_depth_np = cv2.imread(str(depth_filepath), cv2.IMREAD_ANYCOLOR | cv2.IMREAD_ANYDEPTH) I_depth_np = I_depth_np[..., 0] + print(f'\tDepth load took {(time.time() - t) * 1000}ms') I_depth_raw = ImageUInt16(I_depth_np * 32767.5) if I_depth_np.size == 0: print('Could not successfully read the depth image') @@ -102,13 +105,15 @@ def read_data(exp_config: MBTConfig, cam_depth: CameraParameters | None, I: Imag point_cloud[..., 0] = xs * Z point_cloud[..., 1] = ys * Z point_cloud[..., 2] = Z - print(f'Point_cloud took {time.time() - t}') + print(f'\tPoint_cloud took {(time.time() - t) * 1000}ms') cMo_ground_truth = HomogeneousMatrix() ground_truth_file = exp_config.ground_truth_dir / (exp_config.color_camera_name + '_{:04d}.txt'.format(iteration)) cMo_ground_truth.load(str(ground_truth_file)) iteration += 1 + end_parse_time = time.time() + print(f'Data parsing took: {(end_parse_time - start_parse_time) * 1000}ms') yield FrameData(I, I_depth_raw, point_cloud, cMo_ground_truth) @@ -190,7 +195,7 @@ def parse_camera_file(exp_config: MBTConfig, is_color: bool) -> CameraParameters tracker.initFromPose(I, frame_data.cMo_ground_truth) else: tracker.initClick(I, str(mbt_model.init_file)) - + start_time = time.time() for frame_data in data_generator: if frame_data.I_depth is not None: ImageConvert.createDepthHistogram(frame_data.I_depth, I_depth) @@ -208,7 +213,7 @@ def parse_camera_file(exp_config: MBTConfig, is_color: bool) -> CameraParameters } t = time.time() tracker.track(image_dict, {'Camera2': pc}) - print(f'Tracking took {time.time() - t}s') + print(f'Tracking took {(time.time() - t) * 1000}ms') cMo = HomogeneousMatrix() tracker.getPose(cMo) @@ -219,3 +224,5 @@ def parse_camera_file(exp_config: MBTConfig, is_color: bool) -> CameraParameters Display.flush(I_depth) if args.step_by_step: Display.getKeyboardEvent(I, blocking=True) + end_time = time.time() + print(f'total time = {end_time - start_time}') diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbDepthDenseTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbDepthDenseTracker.h index 0dd98709d4..84d1ceb81f 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbDepthDenseTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbDepthDenseTracker.h @@ -168,5 +168,6 @@ class VISP_EXPORT vpMbDepthDenseTracker : public virtual vpMbTracker void segmentPointCloud(const pcl::PointCloud::ConstPtr &point_cloud); #endif void segmentPointCloud(const std::vector &point_cloud, unsigned int width, unsigned int height); + void segmentPointCloud(const vpMatrix &point_cloud, unsigned int width, unsigned int height); }; #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbDepthNormalTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbDepthNormalTracker.h index c48d2fd5f4..ed3cca7ab3 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbDepthNormalTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbDepthNormalTracker.h @@ -183,5 +183,6 @@ class VISP_EXPORT vpMbDepthNormalTracker : public virtual vpMbTracker void segmentPointCloud(const pcl::PointCloud::ConstPtr &point_cloud); #endif void segmentPointCloud(const std::vector &point_cloud, unsigned int width, unsigned int height); + void segmentPointCloud(const vpMatrix &point_cloud, unsigned int width, unsigned int height); }; #endif diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h b/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h index 393ae1691e..b4086d14ee 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbGenericTracker.h @@ -606,6 +606,15 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker std::map &mapOfPointCloudWidths, std::map &mapOfPointCloudHeights); + virtual void track(std::map *> &mapOfImages, + std::map &mapOfPointClouds, + std::map &mapOfPointCloudWidths, + std::map &mapOfPointCloudHeights); + virtual void track(std::map *> &mapOfColorImages, + std::map &mapOfPointClouds, + std::map &mapOfPointCloudWidths, + std::map &mapOfPointCloudHeights); + protected: virtual void computeProjectionError(); @@ -642,6 +651,10 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker std::map *> &mapOfPointClouds, std::map &mapOfPointCloudWidths, std::map &mapOfPointCloudHeights); + virtual void preTracking(std::map *> &mapOfImages, + std::map &mapOfPointClouds, + std::map &mapOfPointCloudWidths, + std::map &mapOfPointCloudHeights); private: class TrackerWrapper : public vpMbEdgeTracker, @@ -770,6 +783,9 @@ class VISP_EXPORT vpMbGenericTracker : public vpMbTracker virtual void preTracking(const vpImage *const ptr_I = nullptr, const std::vector *const point_cloud = nullptr, const unsigned int pointcloud_width = 0, const unsigned int pointcloud_height = 0); + virtual void preTracking(const vpImage *const ptr_I = nullptr, + const vpMatrix *const point_cloud = nullptr, + const unsigned int pointcloud_width = 0, const unsigned int pointcloud_height = 0); virtual void reInitModel(const vpImage *const I, const vpImage *const I_color, const std::string &cad_name, const vpHomogeneousMatrix &cMo, bool verbose = false, diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthDense.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthDense.h index 0ae0eea302..beb1f433b6 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthDense.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthDense.h @@ -53,7 +53,8 @@ class VISP_EXPORT vpMbtFaceDepthDense { public: - enum vpDepthDenseFilteringType { + enum vpDepthDenseFilteringType + { NO_FILTERING = 0, ///< Face is used if visible DEPTH_OCCUPANCY_RATIO_FILTERING = 1 << 1, ///< Face is used if there is ///< enough depth information in @@ -103,6 +104,14 @@ class VISP_EXPORT vpMbtFaceDepthDense #if DEBUG_DISPLAY_DEPTH_DENSE , vpImage &debugImage, std::vector > &roiPts_vec +#endif + , + const vpImage *mask = nullptr); + bool computeDesiredFeatures(const vpHomogeneousMatrix &cMo, unsigned int width, unsigned int height, + const vpMatrix &point_cloud, unsigned int stepX, unsigned int stepY +#if DEBUG_DISPLAY_DEPTH_DENSE + , + vpImage &debugImage, std::vector > &roiPts_vec #endif , const vpImage *mask = nullptr); @@ -146,7 +155,8 @@ class VISP_EXPORT vpMbtFaceDepthDense { if (occupancyRatio < 0.0 || occupancyRatio > 1.0) { std::cerr << "occupancyRatio < 0.0 || occupancyRatio > 1.0" << std::endl; - } else { + } + else { m_depthDenseFilteringOccupancyRatio = occupancyRatio; } } @@ -168,7 +178,7 @@ class VISP_EXPORT vpMbtFaceDepthDense //! The second extremity clipped in the image frame vpImagePoint m_imPt2; - PolygonLine() : m_p1(nullptr), m_p2(nullptr), m_poly(), m_imPt1(), m_imPt2() {} + PolygonLine() : m_p1(nullptr), m_p2(nullptr), m_poly(), m_imPt1(), m_imPt2() { } PolygonLine(const PolygonLine &polyLine) : m_p1(nullptr), m_p2(nullptr), m_poly(polyLine.m_poly), m_imPt1(polyLine.m_imPt1), m_imPt2(polyLine.m_imPt2) diff --git a/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthNormal.h b/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthNormal.h index db5a673d70..7b59a9b625 100644 --- a/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthNormal.h +++ b/modules/tracker/mbt/include/visp3/mbt/vpMbtFaceDepthNormal.h @@ -53,12 +53,14 @@ class VISP_EXPORT vpMbtFaceDepthNormal { public: - enum vpFaceCentroidType { + enum vpFaceCentroidType + { GEOMETRIC_CENTROID, ///< Compute the geometric centroid MEAN_CENTROID ///< Compute the mean centroid }; - enum vpFeatureEstimationType { + enum vpFeatureEstimationType + { ROBUST_FEATURE_ESTIMATION = 0, ROBUST_SVD_PLANE_ESTIMATION = 1, #ifdef VISP_HAVE_PCL @@ -106,6 +108,15 @@ class VISP_EXPORT vpMbtFaceDepthNormal #if DEBUG_DISPLAY_DEPTH_NORMAL , vpImage &debugImage, std::vector > &roiPts_vec +#endif + , + const vpImage *mask = nullptr); + bool computeDesiredFeatures(const vpHomogeneousMatrix &cMo, unsigned int width, unsigned int height, + const vpMatrix &point_cloud, vpColVector &desired_features, + unsigned int stepX, unsigned int stepY +#if DEBUG_DISPLAY_DEPTH_NORMAL + , + vpImage &debugImage, std::vector > &roiPts_vec #endif , const vpImage *mask = nullptr); @@ -179,7 +190,7 @@ class VISP_EXPORT vpMbtFaceDepthNormal //! The second extremity clipped in the image frame vpImagePoint m_imPt2; - PolygonLine() : m_p1(nullptr), m_p2(nullptr), m_poly(), m_imPt1(), m_imPt2() {} + PolygonLine() : m_p1(nullptr), m_p2(nullptr), m_poly(), m_imPt1(), m_imPt2() { } PolygonLine(const PolygonLine &polyLine) : m_p1(nullptr), m_p2(nullptr), m_poly(polyLine.m_poly), m_imPt1(polyLine.m_imPt1), m_imPt2(polyLine.m_imPt2) @@ -211,7 +222,7 @@ class VISP_EXPORT vpMbtFaceDepthNormal public: std::vector data; - Mat33() : data(9) {} + Mat33() : data(9) { } inline T operator[](const size_t i) const { return data[i]; } @@ -221,7 +232,7 @@ class VISP_EXPORT vpMbtFaceDepthNormal { // determinant T det = data[0] * (data[4] * data[8] - data[7] * data[5]) - data[1] * (data[3] * data[8] - data[5] * data[6]) + - data[2] * (data[3] * data[7] - data[4] * data[6]); + data[2] * (data[3] * data[7] - data[4] * data[6]); T invdet = 1 / det; Mat33 minv; @@ -305,7 +316,7 @@ class VISP_EXPORT vpMbtFaceDepthNormal #ifdef VISP_HAVE_NLOHMANN_JSON #include #ifdef VISP_HAVE_PCL -NLOHMANN_JSON_SERIALIZE_ENUM( vpMbtFaceDepthNormal::vpFeatureEstimationType, { +NLOHMANN_JSON_SERIALIZE_ENUM(vpMbtFaceDepthNormal::vpFeatureEstimationType, { {vpMbtFaceDepthNormal::ROBUST_FEATURE_ESTIMATION, "robust"}, {vpMbtFaceDepthNormal::ROBUST_SVD_PLANE_ESTIMATION, "robustSVD"}, {vpMbtFaceDepthNormal::PCL_PLANE_ESTIMATION, "pcl"} diff --git a/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp b/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp index ca74cdc202..db38947bd9 100644 --- a/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp +++ b/modules/tracker/mbt/src/depth/vpMbDepthDenseTracker.cpp @@ -54,11 +54,11 @@ vpMbDepthDenseTracker::vpMbDepthDenseTracker() : m_depthDenseHiddenFacesDisplay(), m_depthDenseListOfActiveFaces(), m_denseDepthNbFeatures(0), m_depthDenseFaces(), - m_depthDenseSamplingStepX(2), m_depthDenseSamplingStepY(2), m_error_depthDense(), m_L_depthDense(), - m_robust_depthDense(), m_w_depthDense(), m_weightedError_depthDense() + m_depthDenseSamplingStepX(2), m_depthDenseSamplingStepY(2), m_error_depthDense(), m_L_depthDense(), + m_robust_depthDense(), m_w_depthDense(), m_weightedError_depthDense() #if DEBUG_DISPLAY_DEPTH_DENSE - , - m_debugDisp_depthDense(nullptr), m_debugImage_depthDense() + , + m_debugDisp_depthDense(nullptr), m_debugImage_depthDense() #endif { #ifdef VISP_HAVE_OGRE @@ -287,7 +287,7 @@ void vpMbDepthDenseTracker::display(const vpImage &I, const vpHom bool displayFullModel) { std::vector > models = - vpMbDepthDenseTracker::getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); + vpMbDepthDenseTracker::getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); for (size_t i = 0; i < models.size(); i++) { if (vpMath::equal(models[i][0], 0)) { @@ -303,7 +303,7 @@ void vpMbDepthDenseTracker::display(const vpImage &I, const vpHomogeneou bool displayFullModel) { std::vector > models = - vpMbDepthDenseTracker::getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); + vpMbDepthDenseTracker::getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); for (size_t i = 0; i < models.size(); i++) { if (vpMath::equal(models[i][0], 0)) { @@ -352,7 +352,7 @@ std::vector > vpMbDepthDenseTracker::getModelForDisplay(unsi ++it) { vpMbtFaceDepthDense *face_dense = *it; std::vector > modelLines = - face_dense->getModelForDisplay(width, height, cMo, cam, displayFullModel); + face_dense->getModelForDisplay(width, height, cMo, cam, displayFullModel); models.insert(models.end(), modelLines.begin(), modelLines.end()); } @@ -368,7 +368,8 @@ void vpMbDepthDenseTracker::init(const vpImage &I) bool reInitialisation = false; if (!useOgre) { faces.setVisible(I.getWidth(), I.getHeight(), m_cam, m_cMo, angleAppears, angleDisappears, reInitialisation); - } else { + } + else { #ifdef VISP_HAVE_OGRE if (!faces.isOgreInitialised()) { faces.setBackgroundSizeOgre(I.getHeight(), I.getWidth()); @@ -408,7 +409,8 @@ void vpMbDepthDenseTracker::loadConfigFile(const std::string &configFile, bool v std::cout << " *********** Parsing XML for Mb Depth Dense Tracker ************ " << std::endl; } xmlp.parse(configFile); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Exception: " << e.what() << std::endl; throw vpException(vpException::ioError, "Cannot open XML file \"%s\"", configFile.c_str()); } @@ -658,6 +660,65 @@ void vpMbDepthDenseTracker::segmentPointCloud(const std::vector &po #endif } + +void vpMbDepthDenseTracker::segmentPointCloud(const vpMatrix &point_cloud, unsigned int width, + unsigned int height) +{ + m_depthDenseListOfActiveFaces.clear(); + +#if DEBUG_DISPLAY_DEPTH_DENSE + if (!m_debugDisp_depthDense->isInitialised()) { + m_debugImage_depthDense.resize(height, width); + m_debugDisp_depthDense->init(m_debugImage_depthDense, 50, 0, "Debug display dense depth tracker"); + } + + m_debugImage_depthDense = 0; + std::vector > roiPts_vec; +#endif + + for (std::vector::iterator it = m_depthDenseFaces.begin(); it != m_depthDenseFaces.end(); + ++it) { + vpMbtFaceDepthDense *face = *it; + + if (face->isVisible() && face->isTracked()) { +#if DEBUG_DISPLAY_DEPTH_DENSE + std::vector > roiPts_vec_; +#endif + if (face->computeDesiredFeatures(m_cMo, width, height, point_cloud, m_depthDenseSamplingStepX, + m_depthDenseSamplingStepY +#if DEBUG_DISPLAY_DEPTH_DENSE + , + m_debugImage_depthDense, roiPts_vec_ +#endif + , + m_mask)) { + m_depthDenseListOfActiveFaces.push_back(*it); + +#if DEBUG_DISPLAY_DEPTH_DENSE + roiPts_vec.insert(roiPts_vec.end(), roiPts_vec_.begin(), roiPts_vec_.end()); +#endif + } + } + } + +#if DEBUG_DISPLAY_DEPTH_DENSE + vpDisplay::display(m_debugImage_depthDense); + + for (size_t i = 0; i < roiPts_vec.size(); i++) { + if (roiPts_vec[i].empty()) + continue; + + for (size_t j = 0; j < roiPts_vec[i].size() - 1; j++) { + vpDisplay::displayLine(m_debugImage_depthDense, roiPts_vec[i][j], roiPts_vec[i][j + 1], vpColor::red, 2); + } + vpDisplay::displayLine(m_debugImage_depthDense, roiPts_vec[i][0], roiPts_vec[i][roiPts_vec[i].size() - 1], + vpColor::red, 2); + } + + vpDisplay::flush(m_debugImage_depthDense); +#endif +} + void vpMbDepthDenseTracker::setOgreVisibilityTest(const bool &v) { vpMbTracker::setOgreVisibilityTest(v); @@ -710,7 +771,7 @@ void vpMbDepthDenseTracker::setUseDepthDenseTracking(const std::string &name, co } } -void vpMbDepthDenseTracker::testTracking() {} +void vpMbDepthDenseTracker::testTracking() { } void vpMbDepthDenseTracker::track(const vpImage &) { diff --git a/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp b/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp index 0901245fca..2b349c8c12 100644 --- a/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp +++ b/modules/tracker/mbt/src/depth/vpMbDepthNormalTracker.cpp @@ -54,14 +54,14 @@ vpMbDepthNormalTracker::vpMbDepthNormalTracker() : m_depthNormalFeatureEstimationMethod(vpMbtFaceDepthNormal::ROBUST_FEATURE_ESTIMATION), - m_depthNormalHiddenFacesDisplay(), m_depthNormalListOfActiveFaces(), m_depthNormalListOfDesiredFeatures(), - m_depthNormalFaces(), m_depthNormalPclPlaneEstimationMethod(2), m_depthNormalPclPlaneEstimationRansacMaxIter(200), - m_depthNormalPclPlaneEstimationRansacThreshold(0.001), m_depthNormalSamplingStepX(2), m_depthNormalSamplingStepY(2), - m_depthNormalUseRobust(false), m_error_depthNormal(), m_featuresToBeDisplayedDepthNormal(), m_L_depthNormal(), - m_robust_depthNormal(), m_w_depthNormal(), m_weightedError_depthNormal() + m_depthNormalHiddenFacesDisplay(), m_depthNormalListOfActiveFaces(), m_depthNormalListOfDesiredFeatures(), + m_depthNormalFaces(), m_depthNormalPclPlaneEstimationMethod(2), m_depthNormalPclPlaneEstimationRansacMaxIter(200), + m_depthNormalPclPlaneEstimationRansacThreshold(0.001), m_depthNormalSamplingStepX(2), m_depthNormalSamplingStepY(2), + m_depthNormalUseRobust(false), m_error_depthNormal(), m_featuresToBeDisplayedDepthNormal(), m_L_depthNormal(), + m_robust_depthNormal(), m_w_depthNormal(), m_weightedError_depthNormal() #if DEBUG_DISPLAY_DEPTH_NORMAL - , - m_debugDisp_depthNormal(nullptr), m_debugImage_depthNormal() + , + m_debugDisp_depthNormal(nullptr), m_debugImage_depthNormal() #endif { #ifdef VISP_HAVE_OGRE @@ -282,7 +282,7 @@ void vpMbDepthNormalTracker::display(const vpImage &I, const vpHo bool displayFullModel) { std::vector > models = - vpMbDepthNormalTracker::getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); + vpMbDepthNormalTracker::getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); for (size_t i = 0; i < models.size(); i++) { if (vpMath::equal(models[i][0], 0)) { @@ -308,7 +308,7 @@ void vpMbDepthNormalTracker::display(const vpImage &I, const vpHomogeneo bool displayFullModel) { std::vector > models = - vpMbDepthNormalTracker::getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); + vpMbDepthNormalTracker::getModelForDisplay(I.getWidth(), I.getHeight(), cMo, cam, displayFullModel); for (size_t i = 0; i < models.size(); i++) { if (vpMath::equal(models[i][0], 0)) { @@ -381,7 +381,7 @@ std::vector > vpMbDepthNormalTracker::getModelForDisplay(uns it != m_depthNormalFaces.end(); ++it) { vpMbtFaceDepthNormal *face_normal = *it; std::vector > modelLines = - face_normal->getModelForDisplay(width, height, cMo, cam, displayFullModel); + face_normal->getModelForDisplay(width, height, cMo, cam, displayFullModel); models.insert(models.end(), modelLines.begin(), modelLines.end()); } @@ -397,7 +397,8 @@ void vpMbDepthNormalTracker::init(const vpImage &I) bool reInitialisation = false; if (!useOgre) { faces.setVisible(I.getWidth(), I.getHeight(), m_cam, m_cMo, angleAppears, angleDisappears, reInitialisation); - } else { + } + else { #ifdef VISP_HAVE_OGRE if (!faces.isOgreInitialised()) { faces.setBackgroundSizeOgre(I.getHeight(), I.getWidth()); @@ -441,7 +442,8 @@ void vpMbDepthNormalTracker::loadConfigFile(const std::string &configFile, bool std::cout << " *********** Parsing XML for Mb Depth Tracker ************ " << std::endl; } xmlp.parse(configFile); - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Exception: " << e.what() << std::endl; throw vpException(vpException::ioError, "Cannot open XML file \"%s\"", configFile.c_str()); } @@ -584,7 +586,7 @@ void vpMbDepthNormalTracker::setUseDepthNormalTracking(const std::string &name, } } -void vpMbDepthNormalTracker::testTracking() {} +void vpMbDepthNormalTracker::testTracking() { } #ifdef VISP_HAVE_PCL void vpMbDepthNormalTracker::segmentPointCloud(const pcl::PointCloud::ConstPtr &point_cloud) @@ -712,6 +714,69 @@ void vpMbDepthNormalTracker::segmentPointCloud(const std::vector &p #endif } +void vpMbDepthNormalTracker::segmentPointCloud(const vpMatrix &point_cloud, unsigned int width, + unsigned int height) +{ + m_depthNormalListOfActiveFaces.clear(); + m_depthNormalListOfDesiredFeatures.clear(); + +#if DEBUG_DISPLAY_DEPTH_NORMAL + if (!m_debugDisp_depthNormal->isInitialised()) { + m_debugImage_depthNormal.resize(height, width); + m_debugDisp_depthNormal->init(m_debugImage_depthNormal, 50, 0, "Debug display normal depth tracker"); + } + + m_debugImage_depthNormal = 0; + std::vector > roiPts_vec; +#endif + + for (std::vector::iterator it = m_depthNormalFaces.begin(); it != m_depthNormalFaces.end(); + ++it) { + vpMbtFaceDepthNormal *face = *it; + + if (face->isVisible() && face->isTracked()) { + vpColVector desired_features; + +#if DEBUG_DISPLAY_DEPTH_NORMAL + std::vector > roiPts_vec_; +#endif + + if (face->computeDesiredFeatures(m_cMo, width, height, point_cloud, desired_features, m_depthNormalSamplingStepX, + m_depthNormalSamplingStepY +#if DEBUG_DISPLAY_DEPTH_NORMAL + , + m_debugImage_depthNormal, roiPts_vec_ +#endif + , + m_mask)) { + m_depthNormalListOfDesiredFeatures.push_back(desired_features); + m_depthNormalListOfActiveFaces.push_back(face); + +#if DEBUG_DISPLAY_DEPTH_NORMAL + roiPts_vec.insert(roiPts_vec.end(), roiPts_vec_.begin(), roiPts_vec_.end()); +#endif + } + } + } + +#if DEBUG_DISPLAY_DEPTH_NORMAL + vpDisplay::display(m_debugImage_depthNormal); + + for (size_t i = 0; i < roiPts_vec.size(); i++) { + if (roiPts_vec[i].empty()) + continue; + + for (size_t j = 0; j < roiPts_vec[i].size() - 1; j++) { + vpDisplay::displayLine(m_debugImage_depthNormal, roiPts_vec[i][j], roiPts_vec[i][j + 1], vpColor::red, 2); + } + vpDisplay::displayLine(m_debugImage_depthNormal, roiPts_vec[i][0], roiPts_vec[i][roiPts_vec[i].size() - 1], + vpColor::red, 2); + } + + vpDisplay::flush(m_debugImage_depthNormal); +#endif +} + void vpMbDepthNormalTracker::setCameraParameters(const vpCameraParameters &cam) { m_cam = cam; diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp index 0dacb833f1..7d0249cdc2 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthDense.cpp @@ -421,6 +421,91 @@ bool vpMbtFaceDepthDense::computeDesiredFeatures(const vpHomogeneousMatrix &cMo, return true; } +bool vpMbtFaceDepthDense::computeDesiredFeatures(const vpHomogeneousMatrix &cMo, unsigned int width, + unsigned int height, const vpMatrix &point_cloud, + unsigned int stepX, unsigned int stepY +#if DEBUG_DISPLAY_DEPTH_DENSE + , + vpImage &debugImage, + std::vector > &roiPts_vec +#endif + , + const vpImage *mask) +{ + m_pointCloudFace.clear(); + + if (width == 0 || height == 0) + return 0; + + std::vector roiPts; + double distanceToFace; + computeROI(cMo, width, height, roiPts +#if DEBUG_DISPLAY_DEPTH_DENSE + , + roiPts_vec +#endif + , + distanceToFace); + + if (roiPts.size() <= 2) { +#ifndef NDEBUG + std::cerr << "Error: roiPts.size() <= 2 in computeDesiredFeatures" << std::endl; +#endif + return false; + } + + if (((m_depthDenseFilteringMethod & MAX_DISTANCE_FILTERING) && distanceToFace > m_depthDenseFilteringMaxDist) || + ((m_depthDenseFilteringMethod & MIN_DISTANCE_FILTERING) && distanceToFace < m_depthDenseFilteringMinDist)) { + return false; + } + + vpPolygon polygon_2d(roiPts); + vpRect bb = polygon_2d.getBoundingBox(); + + unsigned int top = (unsigned int)std::max(0.0, bb.getTop()); + unsigned int bottom = (unsigned int)std::min((double)height, std::max(0.0, bb.getBottom())); + unsigned int left = (unsigned int)std::max(0.0, bb.getLeft()); + unsigned int right = (unsigned int)std::min((double)width, std::max(0.0, bb.getRight())); + + bb.setTop(top); + bb.setBottom(bottom); + bb.setLeft(left); + bb.setRight(right); + + m_pointCloudFace.reserve((size_t)(bb.getWidth() * bb.getHeight())); + + int totalTheoreticalPoints = 0, totalPoints = 0; + for (unsigned int i = top; i < bottom; i += stepY) { + for (unsigned int j = left; j < right; j += stepX) { + if ((m_useScanLine ? (i < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getHeight() && + j < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getWidth() && + m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs()[i][j] == m_polygon->getIndex()) + : polygon_2d.isInside(vpImagePoint(i, j)))) { + totalTheoreticalPoints++; + + if (vpMeTracker::inMask(mask, i, j) && point_cloud[i * width + j][2] > 0) { + totalPoints++; + + m_pointCloudFace.push_back(point_cloud[i * width + j][0]); + m_pointCloudFace.push_back(point_cloud[i * width + j][1]); + m_pointCloudFace.push_back(point_cloud[i * width + j][2]); + +#if DEBUG_DISPLAY_DEPTH_DENSE + debugImage[i][j] = 255; +#endif + } + } + } + } + + if (totalPoints == 0 || ((m_depthDenseFilteringMethod & DEPTH_OCCUPANCY_RATIO_FILTERING) && + totalPoints / (double)totalTheoreticalPoints < m_depthDenseFilteringOccupancyRatio)) { + return false; + } + + return true; +} + void vpMbtFaceDepthDense::computeVisibility() { m_isVisible = m_polygon->isVisible(); } void vpMbtFaceDepthDense::computeVisibilityDisplay() diff --git a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp index faee1d75d3..b741766410 100644 --- a/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp +++ b/modules/tracker/mbt/src/depth/vpMbtFaceDepthNormal.cpp @@ -475,6 +475,166 @@ bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo return true; } +bool vpMbtFaceDepthNormal::computeDesiredFeatures(const vpHomogeneousMatrix &cMo, unsigned int width, + unsigned int height, const vpMatrix &point_cloud, + vpColVector &desired_features, unsigned int stepX, unsigned int stepY +#if DEBUG_DISPLAY_DEPTH_NORMAL + , + vpImage &debugImage, + std::vector > &roiPts_vec +#endif + , + const vpImage *mask) +{ + m_faceActivated = false; + + if (width == 0 || height == 0) + return false; + + std::vector roiPts; + vpColVector desired_normal(3); + + computeROI(cMo, width, height, roiPts +#if DEBUG_DISPLAY_DEPTH_NORMAL + , + roiPts_vec +#endif + ); + + if (roiPts.size() <= 2) { +#ifndef NDEBUG + std::cerr << "Error: roiPts.size() <= 2 in computeDesiredFeatures" << std::endl; +#endif + return false; + } + + vpPolygon polygon_2d(roiPts); + vpRect bb = polygon_2d.getBoundingBox(); + + unsigned int top = (unsigned int)std::max(0.0, bb.getTop()); + unsigned int bottom = (unsigned int)std::min((double)height, std::max(0.0, bb.getBottom())); + unsigned int left = (unsigned int)std::max(0.0, bb.getLeft()); + unsigned int right = (unsigned int)std::min((double)width, std::max(0.0, bb.getRight())); + + bb.setTop(top); + bb.setBottom(bottom); + bb.setLeft(left); + bb.setRight(right); + + // Keep only 3D points inside the projected polygon face + std::vector point_cloud_face, point_cloud_face_custom; + + point_cloud_face.reserve((size_t)(3 * bb.getWidth() * bb.getHeight())); + if (m_featureEstimationMethod == ROBUST_FEATURE_ESTIMATION) { + point_cloud_face_custom.reserve((size_t)(3 * bb.getWidth() * bb.getHeight())); + } + + bool checkSSE2 = vpCPUFeatures::checkSSE2(); +#if !USE_SSE + checkSSE2 = false; +#else + bool push = false; + double prev_x, prev_y, prev_z; +#endif + + double x = 0.0, y = 0.0; + for (unsigned int i = top; i < bottom; i += stepY) { + for (unsigned int j = left; j < right; j += stepX) { + if (vpMeTracker::inMask(mask, i, j) && point_cloud[i * width + j][2] > 0 && + (m_useScanLine ? (i < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getHeight() && + j < m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs().getWidth() && + m_hiddenFace->getMbScanLineRenderer().getPrimitiveIDs()[i][j] == m_polygon->getIndex()) + : polygon_2d.isInside(vpImagePoint(i, j)))) { +// Add point + point_cloud_face.push_back(point_cloud[i * width + j][0]); + point_cloud_face.push_back(point_cloud[i * width + j][1]); + point_cloud_face.push_back(point_cloud[i * width + j][2]); + + if (m_featureEstimationMethod == ROBUST_FEATURE_ESTIMATION) { + // Add point for custom method for plane equation estimation + vpPixelMeterConversion::convertPoint(m_cam, j, i, x, y); + + if (checkSSE2) { +#if USE_SSE + if (!push) { + push = true; + prev_x = x; + prev_y = y; + prev_z = point_cloud[i * width + j][2]; + } + else { + push = false; + point_cloud_face_custom.push_back(prev_x); + point_cloud_face_custom.push_back(x); + + point_cloud_face_custom.push_back(prev_y); + point_cloud_face_custom.push_back(y); + + point_cloud_face_custom.push_back(prev_z); + point_cloud_face_custom.push_back(point_cloud[i * width + j][2]); + } +#endif + } + else { + point_cloud_face_custom.push_back(x); + point_cloud_face_custom.push_back(y); + point_cloud_face_custom.push_back(point_cloud[i * width + j][2]); + } + } + +#if DEBUG_DISPLAY_DEPTH_NORMAL + debugImage[i][j] = 255; +#endif + } + } + } + +#if USE_SSE + if (checkSSE2 && push) { + point_cloud_face_custom.push_back(prev_x); + point_cloud_face_custom.push_back(prev_y); + point_cloud_face_custom.push_back(prev_z); + } +#endif + + if (point_cloud_face.empty() && point_cloud_face_custom.empty()) { + return false; + } + + // Face centroid computed by the different methods + vpColVector centroid_point(3); + +#ifdef VISP_HAVE_PCL + if (m_featureEstimationMethod == PCL_PLANE_ESTIMATION) { + pcl::PointCloud::Ptr point_cloud_face_pcl(new pcl::PointCloud); + point_cloud_face_pcl->reserve(point_cloud_face.size() / 3); + + for (size_t i = 0; i < point_cloud_face.size() / 3; i++) { + point_cloud_face_pcl->push_back( + pcl::PointXYZ(point_cloud_face[3 * i], point_cloud_face[3 * i + 1], point_cloud_face[3 * i + 2])); + } + + computeDesiredFeaturesPCL(point_cloud_face_pcl, desired_features, desired_normal, centroid_point); + } + else +#endif + if (m_featureEstimationMethod == ROBUST_SVD_PLANE_ESTIMATION) { + computeDesiredFeaturesSVD(point_cloud_face, cMo, desired_features, desired_normal, centroid_point); + } + else if (m_featureEstimationMethod == ROBUST_FEATURE_ESTIMATION) { + computeDesiredFeaturesRobustFeatures(point_cloud_face_custom, point_cloud_face, cMo, desired_features, + desired_normal, centroid_point); + } + else { + throw vpException(vpException::badValue, "Unknown feature estimation method!"); + } + + computeDesiredNormalAndCentroid(cMo, desired_normal, centroid_point); + + m_faceActivated = true; + + return true; +} #ifdef VISP_HAVE_PCL bool vpMbtFaceDepthNormal::computeDesiredFeaturesPCL(const pcl::PointCloud::ConstPtr &point_cloud_face, vpColVector &desired_features, vpColVector &desired_normal, diff --git a/modules/tracker/mbt/src/vpMbGenericTracker.cpp b/modules/tracker/mbt/src/vpMbGenericTracker.cpp index 830ff1577b..c4004b7c04 100644 --- a/modules/tracker/mbt/src/vpMbGenericTracker.cpp +++ b/modules/tracker/mbt/src/vpMbGenericTracker.cpp @@ -3276,6 +3276,19 @@ void vpMbGenericTracker::preTracking(std::map *> &mapOfImages, + std::map &mapOfPointClouds, + std::map &mapOfPointCloudWidths, + std::map &mapOfPointCloudHeights) +{ + for (std::map::const_iterator it = m_mapOfTrackers.begin(); + it != m_mapOfTrackers.end(); ++it) { + TrackerWrapper *tracker = it->second; + tracker->preTracking(mapOfImages[it->first], mapOfPointClouds[it->first], mapOfPointCloudWidths[it->first], + mapOfPointCloudHeights[it->first]); + } +} + /*! Re-initialize the model used by the tracker. @@ -5754,6 +5767,166 @@ void vpMbGenericTracker::track(std::map *> &m computeProjectionError(); } +void vpMbGenericTracker::track(std::map *> &mapOfImages, + std::map &mapOfPointClouds, + std::map &mapOfPointCloudWidths, + std::map &mapOfPointCloudHeights) +{ + for (std::map::const_iterator it = m_mapOfTrackers.begin(); + it != m_mapOfTrackers.end(); ++it) { + TrackerWrapper *tracker = it->second; + + if ((tracker->m_trackerType & (EDGE_TRACKER | +#if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) + KLT_TRACKER | +#endif + DEPTH_NORMAL_TRACKER | DEPTH_DENSE_TRACKER)) == 0) { + throw vpException(vpException::fatalError, "Bad tracker type: %d", tracker->m_trackerType); + } + + if (tracker->m_trackerType & (EDGE_TRACKER +#if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) + | KLT_TRACKER +#endif + ) && + mapOfImages[it->first] == nullptr) { + throw vpException(vpException::fatalError, "Image pointer is nullptr!"); + } + + if (tracker->m_trackerType & (DEPTH_NORMAL_TRACKER | DEPTH_DENSE_TRACKER) && + (mapOfPointClouds[it->first] == nullptr)) { + throw vpException(vpException::fatalError, "Pointcloud is nullptr!"); + } + } + + preTracking(mapOfImages, mapOfPointClouds, mapOfPointCloudWidths, mapOfPointCloudHeights); + + try { + computeVVS(mapOfImages); + } + catch (...) { + covarianceMatrix = -1; + throw; // throw the original exception + } + + testTracking(); + + for (std::map::const_iterator it = m_mapOfTrackers.begin(); + it != m_mapOfTrackers.end(); ++it) { + TrackerWrapper *tracker = it->second; + + if (tracker->m_trackerType & EDGE_TRACKER && displayFeatures) { + tracker->m_featuresToBeDisplayedEdge = tracker->getFeaturesForDisplayEdge(); + } + + tracker->postTracking(mapOfImages[it->first], mapOfPointCloudWidths[it->first], mapOfPointCloudHeights[it->first]); + + if (displayFeatures) { +#if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) + if (tracker->m_trackerType & KLT_TRACKER) { + tracker->m_featuresToBeDisplayedKlt = tracker->getFeaturesForDisplayKlt(); + } +#endif + + if (tracker->m_trackerType & DEPTH_NORMAL_TRACKER) { + tracker->m_featuresToBeDisplayedDepthNormal = tracker->getFeaturesForDisplayDepthNormal(); + } + } + } + + computeProjectionError(); +} + +/*! + Realize the tracking of the object in the image. + + \throw vpException : if the tracking is supposed to have failed + + \param mapOfColorImages : Map of images. + \param mapOfPointClouds : Map of pointclouds. + \param mapOfPointCloudWidths : Map of pointcloud widths. + \param mapOfPointCloudHeights : Map of pointcloud heights. +*/ +void vpMbGenericTracker::track(std::map *> &mapOfColorImages, + std::map &mapOfPointClouds, + std::map &mapOfPointCloudWidths, + std::map &mapOfPointCloudHeights) +{ + std::map *> mapOfImages; + for (std::map::const_iterator it = m_mapOfTrackers.begin(); + it != m_mapOfTrackers.end(); ++it) { + TrackerWrapper *tracker = it->second; + + if ((tracker->m_trackerType & (EDGE_TRACKER | +#if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) + KLT_TRACKER | +#endif + DEPTH_NORMAL_TRACKER | DEPTH_DENSE_TRACKER)) == 0) { + throw vpException(vpException::fatalError, "Bad tracker type: %d", tracker->m_trackerType); + } + + if (tracker->m_trackerType & (EDGE_TRACKER +#if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) + | KLT_TRACKER +#endif + ) && + mapOfColorImages[it->first] == nullptr) { + throw vpException(vpException::fatalError, "Image pointer is nullptr!"); + } + else if (tracker->m_trackerType & (EDGE_TRACKER +#if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) + | KLT_TRACKER +#endif + ) && + mapOfColorImages[it->first] != nullptr) { + vpImageConvert::convert(*mapOfColorImages[it->first], tracker->m_I); + mapOfImages[it->first] = &tracker->m_I; // update grayscale image buffer + } + + if (tracker->m_trackerType & (DEPTH_NORMAL_TRACKER | DEPTH_DENSE_TRACKER) && + (mapOfPointClouds[it->first] == nullptr)) { + throw vpException(vpException::fatalError, "Pointcloud is nullptr!"); + } + } + + preTracking(mapOfImages, mapOfPointClouds, mapOfPointCloudWidths, mapOfPointCloudHeights); + + try { + computeVVS(mapOfImages); + } + catch (...) { + covarianceMatrix = -1; + throw; // throw the original exception + } + + testTracking(); + + for (std::map::const_iterator it = m_mapOfTrackers.begin(); + it != m_mapOfTrackers.end(); ++it) { + TrackerWrapper *tracker = it->second; + + if (tracker->m_trackerType & EDGE_TRACKER && displayFeatures) { + tracker->m_featuresToBeDisplayedEdge = tracker->getFeaturesForDisplayEdge(); + } + + tracker->postTracking(mapOfImages[it->first], mapOfPointCloudWidths[it->first], mapOfPointCloudHeights[it->first]); + + if (displayFeatures) { +#if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) + if (tracker->m_trackerType & KLT_TRACKER) { + tracker->m_featuresToBeDisplayedKlt = tracker->getFeaturesForDisplayKlt(); + } +#endif + + if (tracker->m_trackerType & DEPTH_NORMAL_TRACKER) { + tracker->m_featuresToBeDisplayedDepthNormal = tracker->getFeaturesForDisplayDepthNormal(); + } + } + } + + computeProjectionError(); +} + /** TrackerWrapper **/ vpMbGenericTracker::TrackerWrapper::TrackerWrapper() : m_error(), m_L(), m_trackerType(EDGE_TRACKER), m_w(), m_weightedError() @@ -6831,6 +7004,54 @@ void vpMbGenericTracker::TrackerWrapper::preTracking(const vpImage *const ptr_I, + const vpMatrix *const point_cloud, + const unsigned int pointcloud_width, + const unsigned int pointcloud_height) +{ + if (m_trackerType & EDGE_TRACKER) { + try { + vpMbEdgeTracker::trackMovingEdge(*ptr_I); + } + catch (...) { + std::cerr << "Error in moving edge tracking" << std::endl; + throw; + } + } + +#if defined(VISP_HAVE_MODULE_KLT) && defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) && defined(HAVE_OPENCV_VIDEO) + if (m_trackerType & KLT_TRACKER) { + try { + vpMbKltTracker::preTracking(*ptr_I); + } + catch (const vpException &e) { + std::cerr << "Error in KLT tracking: " << e.what() << std::endl; + throw; + } + } +#endif + + if (m_trackerType & DEPTH_NORMAL_TRACKER) { + try { + vpMbDepthNormalTracker::segmentPointCloud(*point_cloud, pointcloud_width, pointcloud_height); + } + catch (...) { + std::cerr << "Error in Depth tracking" << std::endl; + throw; + } + } + + if (m_trackerType & DEPTH_DENSE_TRACKER) { + try { + vpMbDepthDenseTracker::segmentPointCloud(*point_cloud, pointcloud_width, pointcloud_height); + } + catch (...) { + std::cerr << "Error in Depth dense tracking" << std::endl; + throw; + } + } +} + void vpMbGenericTracker::TrackerWrapper::reInitModel(const vpImage *const I, const vpImage *const I_color, const std::string &cad_name, const vpHomogeneousMatrix &cMo, bool verbose,