diff --git a/modules/core/include/visp3/core/vpCannyEdgeDetection.h b/modules/core/include/visp3/core/vpCannyEdgeDetection.h index b2548e5303..c9f7228fc4 100644 --- a/modules/core/include/visp3/core/vpCannyEdgeDetection.h +++ b/modules/core/include/visp3/core/vpCannyEdgeDetection.h @@ -110,7 +110,7 @@ class VISP_EXPORT vpCannyEdgeDetection * Then, compute the x-axis and y-axis gradients of the image. * \param[in] I : The image we want to compute the gradients. */ - void performFilteringAndGradientComputation(const vpImage &I); + void computeFilteringAndGradient(const vpImage &I); /** * \brief Step 3: Edge thining. @@ -214,9 +214,9 @@ class VISP_EXPORT vpCannyEdgeDetection */ friend inline void from_json(const nlohmann::json &j, vpCannyEdgeDetection &detector) { - std::string filteringAndGradientName = vpImageFilter::vpCannyFilteringAndGradientTypeToString(detector.m_filteringAndGradientType); + std::string filteringAndGradientName = vpImageFilter::vpCannyFiltAndGradTypeToStr(detector.m_filteringAndGradientType); filteringAndGradientName = j.value("filteringAndGradientType", filteringAndGradientName); - detector.m_filteringAndGradientType = vpImageFilter::vpCannyFilteringAndGradientTypeFromString(filteringAndGradientName); + detector.m_filteringAndGradientType = vpImageFilter::vpCannyFiltAndGradTypeFromStr(filteringAndGradientName); detector.m_gaussianKernelSize = j.value("gaussianSize", detector.m_gaussianKernelSize); detector.m_gaussianStdev = j.value("gaussianStdev", detector.m_gaussianStdev); detector.m_lowerThreshold = j.value("lowerThreshold", detector.m_lowerThreshold); @@ -234,7 +234,7 @@ class VISP_EXPORT vpCannyEdgeDetection */ friend inline void to_json(nlohmann::json &j, const vpCannyEdgeDetection &detector) { - std::string filteringAndGradientName = vpImageFilter::vpCannyFilteringAndGradientTypeToString(detector.m_filteringAndGradientType); + std::string filteringAndGradientName = vpImageFilter::vpCannyFiltAndGradTypeToStr(detector.m_filteringAndGradientType); j = nlohmann::json { {"filteringAndGradientType", filteringAndGradientName}, {"gaussianSize", detector.m_gaussianKernelSize}, diff --git a/modules/core/include/visp3/core/vpImageFilter.h b/modules/core/include/visp3/core/vpImageFilter.h index ca778c813f..2c658e9ed6 100644 --- a/modules/core/include/visp3/core/vpImageFilter.h +++ b/modules/core/include/visp3/core/vpImageFilter.h @@ -156,12 +156,12 @@ class VISP_EXPORT vpImageFilter CANNY_COUNT_FILTERING = 2 //! Number of supported backends } vpCannyFilteringAndGradientType; - static std::string vpCannyFilteringAndGradientTypeList(const std::string &pref = "<", const std::string &sep = " , ", + static std::string vpGetCannyFiltAndGradTypes(const std::string &pref = "<", const std::string &sep = " , ", const std::string &suf = ">"); - static std::string vpCannyFilteringAndGradientTypeToString(const vpCannyFilteringAndGradientType &type); + static std::string vpCannyFiltAndGradTypeToStr(const vpCannyFilteringAndGradientType &type); - static vpCannyFilteringAndGradientType vpCannyFilteringAndGradientTypeFromString(const std::string &name); + static vpCannyFilteringAndGradientType vpCannyFiltAndGradTypeFromStr(const std::string &name); static void canny(const vpImage &I, vpImage &Ic, const unsigned int &gaussianFilterSize, const float &thresholdCanny, const unsigned int &apertureSobel); @@ -305,7 +305,7 @@ class VISP_EXPORT vpImageFilter } else { std::string errMsg = "[vpImageFilter::computePartialDerivatives] Filtering + gradient method \""; - errMsg += vpCannyFilteringAndGradientTypeToString(filteringType); + errMsg += vpCannyFiltAndGradTypeToStr(filteringType); errMsg += "\" is not implemented yet\n"; throw(vpException(vpException::notImplementedError, errMsg)); } diff --git a/modules/core/src/image/vpCannyEdgeDetection.cpp b/modules/core/src/image/vpCannyEdgeDetection.cpp index dfcbc1a535..c1f55dcec6 100644 --- a/modules/core/src/image/vpCannyEdgeDetection.cpp +++ b/modules/core/src/image/vpCannyEdgeDetection.cpp @@ -171,7 +171,7 @@ vpCannyEdgeDetection::initGradientFilters() } else { std::string errMsg = "[vpCannyEdgeDetection::initGradientFilters] Error: gradient filtering method \""; - errMsg += vpImageFilter::vpCannyFilteringAndGradientTypeToString(m_filteringAndGradientType); + errMsg += vpImageFilter::vpCannyFiltAndGradTypeToStr(m_filteringAndGradientType); errMsg += "\" has not been implemented yet\n"; throw vpException(vpException::notImplementedError, errMsg); } @@ -209,7 +209,7 @@ vpCannyEdgeDetection::detect(const vpImage &I) // // Step 1 and 2: filter the image and compute the gradient, if not given by the user if (!m_areGradientAvailable) { - performFilteringAndGradientComputation(I); + computeFilteringAndGradient(I); } m_areGradientAvailable = false; // Reset for next call @@ -238,7 +238,7 @@ vpCannyEdgeDetection::detect(const vpImage &I) } void -vpCannyEdgeDetection::performFilteringAndGradientComputation(const vpImage &I) +vpCannyEdgeDetection::computeFilteringAndGradient(const vpImage &I) { if ((m_filteringAndGradientType == vpImageFilter::CANNY_GBLUR_SOBEL_FILTERING) || (m_filteringAndGradientType == vpImageFilter::CANNY_GBLUR_SCHARR_FILTERING)) { @@ -254,7 +254,7 @@ vpCannyEdgeDetection::performFilteringAndGradientComputation(const vpImage ignoring the point - continue; - } + // Computing the gradient orientation and magnitude + float grad = getManhattanGradient(m_dIx, m_dIy, row, col); - // Getting the offset along the horizontal and vertical axes - // depending on the gradient orientation - int dRowAlphaPlus = 0, dRowBetaPlus = 0; - int dColAphaPlus = 0, dColBetaPlus = 0; - float gradientOrientation = getGradientOrientation(m_dIx, m_dIy, row, col); - float alpha = 0.f, beta = 0.f; - getInterpolationWeightsAndOffsets(gradientOrientation, alpha, beta, dRowAlphaPlus, dRowBetaPlus, dColAphaPlus, dColBetaPlus); - int dRowAlphaMinus = -dRowAlphaPlus, dRowBetaMinus = -dRowBetaPlus; - int dColAphaMinus = -dColAphaPlus, dColBetaMinus = -dColBetaPlus; - float gradAlphaPlus = getManhattanGradient(m_dIx, m_dIy, row + dRowAlphaPlus, col + dColAphaPlus); - float gradBetaPlus = getManhattanGradient(m_dIx, m_dIy, row + dRowBetaPlus, col + dColBetaPlus); - float gradAlphaMinus = getManhattanGradient(m_dIx, m_dIy, row + dRowAlphaMinus, col + dColAphaMinus); - float gradBetaMinus = getManhattanGradient(m_dIx, m_dIy, row + dRowBetaMinus, col + dColBetaMinus); - float gradPlus = (alpha * gradAlphaPlus) + (beta * gradBetaPlus); - float gradMinus = (alpha * gradAlphaMinus) + (beta * gradBetaMinus); - - if ((grad >= gradPlus) && (grad >= gradMinus)) { - // Keeping the edge point that has the highest gradient - std::pair bestPixel(row, col); - m_edgeCandidateAndGradient[bestPixel] = grad; + if (grad < lowerThreshold) { + // The gradient is lower than minimum threshold => ignoring the point + grad_lower_threshold = true; + // continue + } + if (grad_lower_threshold == false) { + // + // Getting the offset along the horizontal and vertical axes + // depending on the gradient orientation + int dRowAlphaPlus = 0, dRowBetaPlus = 0; + int dColAphaPlus = 0, dColBetaPlus = 0; + float gradientOrientation = getGradientOrientation(m_dIx, m_dIy, row, col); + float alpha = 0.f, beta = 0.f; + getInterpolWeightsAndOffsets(gradientOrientation, alpha, beta, dRowAlphaPlus, dRowBetaPlus, dColAphaPlus, dColBetaPlus); + int dRowAlphaMinus = -dRowAlphaPlus, dRowBetaMinus = -dRowBetaPlus; + int dColAphaMinus = -dColAphaPlus, dColBetaMinus = -dColBetaPlus; + float gradAlphaPlus = getManhattanGradient(m_dIx, m_dIy, row + dRowAlphaPlus, col + dColAphaPlus); + float gradBetaPlus = getManhattanGradient(m_dIx, m_dIy, row + dRowBetaPlus, col + dColBetaPlus); + float gradAlphaMinus = getManhattanGradient(m_dIx, m_dIy, row + dRowAlphaMinus, col + dColAphaMinus); + float gradBetaMinus = getManhattanGradient(m_dIx, m_dIy, row + dRowBetaMinus, col + dColBetaMinus); + float gradPlus = (alpha * gradAlphaPlus) + (beta * gradBetaPlus); + float gradMinus = (alpha * gradAlphaMinus) + (beta * gradBetaMinus); + + if ((grad >= gradPlus) && (grad >= gradMinus)) { + // Keeping the edge point that has the highest gradient + std::pair bestPixel(row, col); + m_edgeCandidateAndGradient[bestPixel] = grad; + } + } } } } @@ -426,7 +439,8 @@ void vpCannyEdgeDetection::performHysteresisThresholding(const float &lowerThreshold, const float &upperThreshold) { std::map, float>::iterator it; - for (it = m_edgeCandidateAndGradient.begin(); it != m_edgeCandidateAndGradient.end(); ++it) { + std::map, float>::iterator m_edgeCandidateAndGradient_end = m_edgeCandidateAndGradient.end(); + for (it = m_edgeCandidateAndGradient.begin(); it != m_edgeCandidateAndGradient_end; ++it) { if (it->second >= upperThreshold) { m_edgePointsCandidates[it->first] = STRONG_EDGE; } @@ -440,7 +454,8 @@ void vpCannyEdgeDetection::performEdgeTracking() { std::map, EdgeType>::iterator it; - for (it = m_edgePointsCandidates.begin(); it != m_edgePointsCandidates.end(); ++it) { + std::map, EdgeType>::iterator m_edgePointsCandidates_end = m_edgePointsCandidates.end(); + for (it = m_edgePointsCandidates.begin(); it != m_edgePointsCandidates_end; ++it) { if (it->second == STRONG_EDGE) { m_edgeMap[it->first.first][it->first.second] = 255; } @@ -459,37 +474,47 @@ vpCannyEdgeDetection::recursiveSearchForStrongEdge(const std::pair(coordinates.first); idRow = std::max(idRow, 0); // Avoid getting negative pixel ID int idCol = dc + static_cast(coordinates.second); idCol = std::max(idCol, 0); // Avoid getting negative pixel ID // Checking if we are still looking for an edge in the limit of the image - if (((idRow < 0) || (idRow >= nbRows)) - || ((idCol < 0) || (idCol >= nbCols)) - || ((dr == 0) && (dc == 0)) - ) { - continue; + test_row = (idRow < 0) || (idRow >= nbRows); + test_col = (idCol < 0) || (idCol >= nbCols); + test_drdc = (dr == 0) && (dc == 0); + if (test_row || test_col || test_drdc) { + edge_in_image_limit = true; + // the continue is replaced by the test } - - try { - std::pair key_candidate(idRow, idCol); - // Checking if the 8-neighbor point is in the list of edge candidates - EdgeType type_candidate = m_edgePointsCandidates.at(key_candidate); - if (type_candidate == STRONG_EDGE) { - // The 8-neighbor point is a strong edge => the weak edge becomes a strong edge - hasFoundStrongEdge = true; + if (edge_in_image_limit == false) { + + try { + std::pair key_candidate(idRow, idCol); + // Checking if the 8-neighbor point is in the list of edge candidates + EdgeType type_candidate = m_edgePointsCandidates.at(key_candidate); + if (type_candidate == STRONG_EDGE) { + // The 8-neighbor point is a strong edge => the weak edge becomes a strong edge + hasFoundStrongEdge = true; + } + else if (type_candidate == WEAK_EDGE) { + // Checking if the WEAK_EDGE neighbor has a STRONG_EDGE neighbor + hasFoundStrongEdge = recursiveSearchForStrongEdge(key_candidate); + } } - else if (type_candidate == WEAK_EDGE) { - // Checking if the WEAK_EDGE neighbor has a STRONG_EDGE neighbor - hasFoundStrongEdge = recursiveSearchForStrongEdge(key_candidate); + catch (...) { + // continue - nothing to do } } - catch (...) { - continue; - } } } if (hasFoundStrongEdge) { diff --git a/modules/core/src/image/vpGaussianFilter.cpp b/modules/core/src/image/vpGaussianFilter.cpp index efba11d42f..8bafec5514 100644 --- a/modules/core/src/image/vpGaussianFilter.cpp +++ b/modules/core/src/image/vpGaussianFilter.cpp @@ -46,14 +46,13 @@ class vpGaussianFilter::Impl : m_funcPtrGray(nullptr), m_funcPtrRGBa(nullptr), m_deinterleave(deinterleave) { const float epsilon = 0.001f; - { - const size_t channels = 1; - m_funcPtrGray = SimdGaussianBlurInit(width, height, channels, &sigma, &epsilon); - } - { - const size_t channels = 4; - m_funcPtrRGBa = SimdGaussianBlurInit(width, height, channels, &sigma, &epsilon); - } + + const size_t channels_1 = 1; + m_funcPtrGray = SimdGaussianBlurInit(width, height, channels_1, &sigma, &epsilon); + + const size_t channels_4 = 4; + m_funcPtrRGBa = SimdGaussianBlurInit(width, height, channels_4, &sigma, &epsilon); + if (m_deinterleave) { m_red.resize(height, width); m_green.resize(height, width); diff --git a/modules/core/src/image/vpImageCircle.cpp b/modules/core/src/image/vpImageCircle.cpp index 7d51888f81..d21fbe1a00 100644 --- a/modules/core/src/image/vpImageCircle.cpp +++ b/modules/core/src/image/vpImageCircle.cpp @@ -66,7 +66,7 @@ vpImageCircle::vpImageCircle(const cv::Vec3f &vec) * \param[in] radius The radius of the circle. * \param[out] delta_theta The length of the angular interval that is in the RoI. */ -void computeIntersectionsLeftBorderOnly(const float &u_c, const float &umin_roi, const float &radius, +void computeIntersectionsLeftBorder(const float &u_c, const float &umin_roi, const float &radius, float &delta_theta) { // --comment: umin_roi = u_c + r cos(theta) @@ -91,7 +91,7 @@ void computeIntersectionsLeftBorderOnly(const float &u_c, const float &umin_roi, * \param[in] radius The radius of the circle. * \param[out] delta_theta The length of the angular interval that is in the RoI. */ -void computeIntersectionsRightBorderOnly(const float &u_c, const float &umax_roi, const float &radius, +void computeIntersectionsRightBorder(const float &u_c, const float &umax_roi, const float &radius, float &delta_theta) { // --comment: u = u_c + r cos(theta) @@ -116,7 +116,7 @@ void computeIntersectionsRightBorderOnly(const float &u_c, const float &umax_roi * \param[in] radius The radius of the circle. * \param[out] delta_theta The length of the angular interval that is in the RoI. */ -void computeIntersectionsTopBorderOnly(const float &v_c, const float &vmin_roi, const float &radius, +void computeIntersectionsTopBorder(const float &v_c, const float &vmin_roi, const float &radius, float &delta_theta) { // v = vc - r sin(theta) because the v-axis goes down @@ -158,7 +158,7 @@ void computeIntersectionsTopBorderOnly(const float &v_c, const float &vmin_roi, * \param[in] radius The radius of the circle. * \param[out] delta_theta The length of the angular interval that is in the RoI. */ -void computeIntersectionsBottomBorderOnly(const float &v_c, const float &vmax_roi, const float &radius, +void computeIntersBottomBorder(const float &v_c, const float &vmax_roi, const float &radius, float &delta_theta) { // v = vc - r sin(theta) because the v-axis goes down @@ -205,7 +205,7 @@ void computeIntersectionsBottomBorderOnly(const float &v_c, const float &vmax_ro * \param[out] theta_v_cross_min The pair angle /v-coordinate for which the circle intersects the v-axis with the lowest v-coordinate; i.e. \b theta_v_cross_min.second < \b theta_v_cross_max.second . * \param[out] theta_v_cross_max The pair angle /v-coordinate for which the circle intersects the v-axis with the highest v-coordinate. */ -void computePerpendicularAxesIntersections(const float &u_c, const float &v_c, const float &radius, +void computePerpendicularAxesInters(const float &u_c, const float &v_c, const float &radius, const float &crossing_u, const float &crossing_v, std::pair &theta_u_cross_min, std::pair &theta_u_cross_max, std::pair &theta_v_cross_min, std::pair &theta_v_cross_max) @@ -282,7 +282,7 @@ void computeIntersectionsTopLeft(const float &u_c, const float &v_c, const float std::pair crossing_theta_v_min, crossing_theta_v_max; float crossing_u = vmin_roi; // We cross the u-axis of the RoI at which v-coordinate float crossing_v = umin_roi; // We cross the v-axis of the RoI at which u-coordinate - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u, crossing_v, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u, crossing_v, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_u_min = crossing_theta_u_min.first, theta_v_min = crossing_theta_v_min.first; @@ -305,13 +305,13 @@ void computeIntersectionsTopLeft(const float &u_c, const float &v_c, const float // The circle crosses the u-axis outside the roi // so it is equivalent to the case of crossing only the left border //Case left only - computeIntersectionsLeftBorderOnly(u_c, umin_roi, radius, delta_theta); + computeIntersectionsLeftBorder(u_c, umin_roi, radius, delta_theta); } else if ((u_umin >= umin_roi) && (u_umax >= umin_roi) && (v_vmin <= vmin_roi) && (v_vmax <= vmin_roi)) { // The circle crosses the v-axis outside the roi // so it is equivalent to the case of crossing only the top border //Case top only - computeIntersectionsTopBorderOnly(v_c, vmin_roi, radius, delta_theta); + computeIntersectionsTopBorder(v_c, vmin_roi, radius, delta_theta); } } @@ -331,7 +331,7 @@ void computeIntersectionsTopRight(const float &u_c, const float &v_c, const floa { std::pair crossing_theta_u_min, crossing_theta_u_max; std::pair crossing_theta_v_min, crossing_theta_v_max; - computePerpendicularAxesIntersections(u_c, v_c, radius, vmin_roi, umax_roi, + computePerpendicularAxesInters(u_c, v_c, radius, vmin_roi, umax_roi, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_u_min = crossing_theta_u_min.first, theta_v_min = crossing_theta_v_min.first; @@ -358,13 +358,13 @@ void computeIntersectionsTopRight(const float &u_c, const float &v_c, const floa // The circle crosses the u-axis outside the roi // so it is equivalent to the case of crossing only the right border //Case crossing right only - computeIntersectionsRightBorderOnly(u_c, umax_roi, radius, delta_theta); + computeIntersectionsRightBorder(u_c, umax_roi, radius, delta_theta); } else if ((u_umin <= umax_roi) && (v_vmin <= vmin_roi) && (u_umax <= umax_roi) && (v_vmax <= vmin_roi)) { // The circle crosses the v-axis outside the roi // so it is equivalent to the case of crossing only the top border //Case crossing top only - computeIntersectionsTopBorderOnly(v_c, vmin_roi, radius, delta_theta); + computeIntersectionsTopBorder(v_c, vmin_roi, radius, delta_theta); } } @@ -386,7 +386,7 @@ void computeIntersectionsBottomLeft(const float &u_c, const float &v_c, const fl std::pair crossing_theta_v_min, crossing_theta_v_max; float crossing_u = vmax_roi; // We cross the u-axis of the RoI at which v-coordinate float crossing_v = umin_roi; // We cross the v-axis of the RoI at which u-coordinate - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u, crossing_v, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u, crossing_v, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_u_min = crossing_theta_u_min.first, theta_v_min = crossing_theta_v_min.first; @@ -409,13 +409,13 @@ void computeIntersectionsBottomLeft(const float &u_c, const float &v_c, const fl // The circle crosses the u-axis outside the roi // so it is equivalent to the case of crossing only the left border //Case left only - computeIntersectionsLeftBorderOnly(u_c, umin_roi, radius, delta_theta); + computeIntersectionsLeftBorder(u_c, umin_roi, radius, delta_theta); } else if ((u_umin >= umin_roi) && (u_umax >= umin_roi) && (v_vmin >= vmax_roi) && (v_vmax >= vmax_roi)) { // The circle crosses the v-axis outside the roi // so it is equivalent to the case of crossing only the bottom border //Case bottom only - computeIntersectionsBottomBorderOnly(v_c, vmax_roi, radius, delta_theta); + computeIntersBottomBorder(v_c, vmax_roi, radius, delta_theta); } } @@ -437,7 +437,7 @@ void computeIntersectionsBottomRight(const float &u_c, const float &v_c, const f std::pair crossing_theta_v_min, crossing_theta_v_max; float crossing_u = vmax_roi; // We cross the u-axis of the RoI at the maximum v-coordinate of the RoI float crossing_v = umax_roi; // We cross the v-axis of the RoI at the maximum u-coordinate of the RoI - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u, crossing_v, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u, crossing_v, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_u_min = crossing_theta_u_min.first, theta_v_min = crossing_theta_v_min.first; @@ -464,13 +464,13 @@ void computeIntersectionsBottomRight(const float &u_c, const float &v_c, const f // The circle crosses the u-axis outside the roi // so it is equivalent to the case of crossing only the right border //Case left only - computeIntersectionsRightBorderOnly(u_c, umax_roi, radius, delta_theta); + computeIntersectionsRightBorder(u_c, umax_roi, radius, delta_theta); } else if ((u_umin <= umax_roi) && (u_umax <= umax_roi) && (v_vmin > vmax_roi) && (v_vmax > vmax_roi)) { // The circle crosses the v-axis outside the roi // so it is equivalent to the case of crossing only the bottom border //Case bottom only - computeIntersectionsBottomBorderOnly(v_c, vmax_roi, radius, delta_theta); + computeIntersBottomBorder(v_c, vmax_roi, radius, delta_theta); } } @@ -486,7 +486,7 @@ void computeIntersectionsBottomRight(const float &u_c, const float &v_c, const f * \param[in] radius The radius of the circle. * \param[out] delta_theta The length of the angular interval that is in the RoI. */ -void computeIntersectionsTopLeftBottom(const float &u_c, const float &v_c, const float &umin_roi, const float &vmin_roi, +void computeIntersTopLeftBottom(const float &u_c, const float &v_c, const float &umin_roi, const float &vmin_roi, const float &vmax_roi, const float &radius, float &delta_theta) { // Computing the intersections with the top and left axes @@ -494,7 +494,7 @@ void computeIntersectionsTopLeftBottom(const float &u_c, const float &v_c, const std::pair crossing_theta_v_min, crossing_theta_v_max; float crossing_u_top = vmin_roi; // We cross the u-axis of the top axis of the RoI at the minimum v-coordinate of the RoI float crossing_v = umin_roi; // We cross the v-axis of the RoI at the minimum u-coordinate of the RoI - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u_top, crossing_v, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u_top, crossing_v, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_u_min_top = crossing_theta_u_min.first, theta_v_min = crossing_theta_v_min.first; @@ -506,7 +506,7 @@ void computeIntersectionsTopLeftBottom(const float &u_c, const float &v_c, const // Computing the intersections with the bottom and left axes float crossing_u_bottom = vmax_roi; // We cross the u-axis of the RoI at the maximum v-coordinate of the RoI - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u_bottom, crossing_v, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u_bottom, crossing_v, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_u_min_bottom = crossing_theta_u_min.first; @@ -523,7 +523,7 @@ void computeIntersectionsTopLeftBottom(const float &u_c, const float &v_c, const } else if ((u_umax_top <= umin_roi) && (u_umax_bottom <= umin_roi) && (v_vmin >= vmin_roi) && (v_vmax <= vmax_roi)) { // case left only - computeIntersectionsLeftBorderOnly(u_c, umin_roi, radius, delta_theta); + computeIntersectionsLeftBorder(u_c, umin_roi, radius, delta_theta); } else if ((u_umax_bottom > umin_roi) && (v_vmin >= vmin_roi)) { // case bottom/left corner @@ -547,7 +547,7 @@ void computeIntersectionsTopLeftBottom(const float &u_c, const float &v_c, const * \param[in] radius The radius of the circle. * \param[out] delta_theta The length of the angular interval that is in the RoI. */ -void computeIntersectionsTopRightBottom(const float &u_c, const float &v_c, const float &umax_roi, const float &vmin_roi, const float &vmax_roi, +void computeIntersTopRightBottom(const float &u_c, const float &v_c, const float &umax_roi, const float &vmin_roi, const float &vmax_roi, const float &radius, float &delta_theta) { // Computing the intersections with the top and right axes @@ -555,7 +555,7 @@ void computeIntersectionsTopRightBottom(const float &u_c, const float &v_c, cons std::pair crossing_theta_v_min, crossing_theta_v_max; float crossing_u_top = vmin_roi; // We cross the u-axis of the top axis of the RoI at the minimum v-coordinate of the RoI float crossing_v = umax_roi; // We cross the v-axis of the right axis of the RoI at the maximum u-coordinate of the RoI - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u_top, crossing_v, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u_top, crossing_v, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_u_min_top = crossing_theta_u_min.first, theta_v_min = crossing_theta_v_min.first; @@ -567,7 +567,7 @@ void computeIntersectionsTopRightBottom(const float &u_c, const float &v_c, cons // Computing the intersections with the bottom and right axes float crossing_u_bottom = vmax_roi; // We cross the u-axis of the RoI at the maximum v-coordinate of the RoI - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u_bottom, crossing_v, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u_bottom, crossing_v, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_u_min_bottom = crossing_theta_u_min.first; @@ -584,7 +584,7 @@ void computeIntersectionsTopRightBottom(const float &u_c, const float &v_c, cons } else if ((u_umin_top >= umax_roi) && (u_umin_bottom >= umax_roi) && (v_vmin >= vmin_roi) && (v_vmax <= vmax_roi)) { // case right only - computeIntersectionsRightBorderOnly(u_c, umax_roi, radius, delta_theta); + computeIntersectionsRightBorder(u_c, umax_roi, radius, delta_theta); } else if ((u_umin_bottom <= umax_roi) && (v_vmin >= vmin_roi)) { // case bottom/right corner @@ -607,7 +607,7 @@ void computeIntersectionsTopRightBottom(const float &u_c, const float &v_c, cons * \param[in] radius The radius of the circle. * \param[out] delta_theta The length of the angular interval that is in the RoI. */ -void computeIntersectionsTopBottomOnly(const float &u_c, const float &v_c, const float &vmin_roi, const float &vmax_roi, const float &radius, +void computeIntersTopBottomOnly(const float &u_c, const float &v_c, const float &vmin_roi, const float &vmax_roi, const float &radius, float &delta_theta) { // Computing the two angles for which the u-axis is crossed at the top of the RoI @@ -682,7 +682,7 @@ void computeIntersectionsTopBottomOnly(const float &u_c, const float &v_c, const * \param[in] radius The radius of the circle. * \param[out] delta_theta The length of the angular interval that is in the RoI. */ -void computeIntersectionsLeftRightTop(const float &u_c, const float &v_c, const float &umin_roi, const float &umax_roi, +void computeIntersLeftRightTop(const float &u_c, const float &v_c, const float &umin_roi, const float &umax_roi, const float &vmin_roi, const float &radius, float &delta_theta) { // Computing the intersections with the top and left axes @@ -690,7 +690,7 @@ void computeIntersectionsLeftRightTop(const float &u_c, const float &v_c, const std::pair crossing_theta_v_min, crossing_theta_v_max; float crossing_u = vmin_roi; // We cross the u-axis of the RoI at the minimum v-coordinate of the RoI float crossing_v_left = umin_roi; // We cross the v-axis of the left of the RoI at the minimum u-coordinate of the RoI - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u, crossing_v_left, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u, crossing_v_left, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_u_min = crossing_theta_u_min.first; @@ -704,7 +704,7 @@ void computeIntersectionsLeftRightTop(const float &u_c, const float &v_c, const // Computing the intersections with the rigt and top axes float crossing_v_right = umax_roi; // We cross the v-axis of the right of the RoI at the maximum u-coordinate of the RoI - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u, crossing_v_right, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u, crossing_v_right, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_v_min_right = crossing_theta_v_min.first; @@ -722,7 +722,7 @@ void computeIntersectionsLeftRightTop(const float &u_c, const float &v_c, const } else if ((v_vmax_left <= vmin_roi) && (v_vmax_right <= vmin_roi) && (u_umin >= umin_roi) && (u_umax <= umax_roi)) { // case top only - computeIntersectionsTopBorderOnly(v_c, vmin_roi, radius, delta_theta); + computeIntersectionsTopBorder(v_c, vmin_roi, radius, delta_theta); } else if ((u_umax >= umin_roi) && (v_vmax_left >= vmin_roi)) { // case top/left corner @@ -746,7 +746,7 @@ void computeIntersectionsLeftRightTop(const float &u_c, const float &v_c, const * \param[in] radius The radius of the circle. * \param[out] delta_theta The length of the angular interval that is in the RoI. */ -void computeIntersectionsLeftRightBottom(const float &u_c, const float &v_c, const float &umin_roi, const float &umax_roi, +void computeIntersLeftRightBottom(const float &u_c, const float &v_c, const float &umin_roi, const float &umax_roi, const float &vmax_roi, const float &radius, float &delta_theta) { // Computing the intersections with the bottom and left axes @@ -754,7 +754,7 @@ void computeIntersectionsLeftRightBottom(const float &u_c, const float &v_c, con std::pair crossing_theta_v_min, crossing_theta_v_max; float crossing_u = vmax_roi; // We cross the u-axis of the bottom axis of the RoI at the maximum v-coordinate of the RoI float crossing_v_left = umin_roi; // We cross the v-axis of the left of the RoI at the minimum u-coordinate of the RoI - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u, crossing_v_left, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u, crossing_v_left, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_u_min = crossing_theta_u_min.first; @@ -768,7 +768,7 @@ void computeIntersectionsLeftRightBottom(const float &u_c, const float &v_c, con // Computing the intersections with the bottom and right axes float crossing_v_right = umax_roi; // We cross the v-axis of the right of the RoI at the maximum u-coordinate of the RoI - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u, crossing_v_right, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u, crossing_v_right, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_v_min_right = crossing_theta_v_min.first; @@ -786,7 +786,7 @@ void computeIntersectionsLeftRightBottom(const float &u_c, const float &v_c, con } else if ((v_vmin_left >= vmax_roi) && (v_vmin_right >= vmax_roi) && (u_umin >= umin_roi) && (u_umax <= umax_roi)) { // case bottom only - computeIntersectionsBottomBorderOnly(v_c, vmax_roi, radius, delta_theta); + computeIntersBottomBorder(v_c, vmax_roi, radius, delta_theta); } else if ((u_umax >= umin_roi) && (v_vmin_right >= vmax_roi)) { // case bottom/left corner @@ -809,7 +809,7 @@ void computeIntersectionsLeftRightBottom(const float &u_c, const float &v_c, con * \param[in] radius The radius of the circle. * \param[out] delta_theta The length of the angular interval that is in the RoI. */ -void computeIntersectionsLeftRightOnly(const float &u_c, const float &v_c, const float &umin_roi, const float &umax_roi, const float &radius, +void computeIntersectionsLeftRight(const float &u_c, const float &v_c, const float &umin_roi, const float &umax_roi, const float &radius, float &delta_theta) { // Computing the two angles for which the v-axis is crossed at the left of the RoI @@ -884,7 +884,7 @@ void computeIntersectionsAllAxes(const float &u_c, const float &v_c, const float std::pair crossing_theta_v_min, crossing_theta_v_max; float crossing_u_top = vmin_roi; // We cross the u-axis of the top axis of the RoI at the minimum v-coordinate of the RoI float crossing_v_left = umin_roi; // We cross the v-axis of the left of the RoI at the minimum u-coordinate of the RoI - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u_top, crossing_v_left, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u_top, crossing_v_left, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_u_min_top = crossing_theta_u_min.first; @@ -895,7 +895,7 @@ void computeIntersectionsAllAxes(const float &u_c, const float &v_c, const float // Computing the intersections with the bottom and right axes float crossing_u_bottom = vmax_roi; // We cross the u-axis of the RoI at the maximum v-coordinate of the RoI float crossing_v_right = umax_roi; // We cross the v-axis of the right of the RoI at the maximum u-coordinate of the RoI - computePerpendicularAxesIntersections(u_c, v_c, radius, crossing_u_bottom, crossing_v_right, + computePerpendicularAxesInters(u_c, v_c, radius, crossing_u_bottom, crossing_v_right, crossing_theta_u_min, crossing_theta_u_max, crossing_theta_v_min, crossing_theta_v_max); float theta_u_min_bottom = crossing_theta_u_min.first; @@ -934,19 +934,19 @@ float vpImageCircle::computeAngularCoverageInRoI(const vpRect &roi, const float } else if (touchBottomBorder && (!touchLeftBorder) && (!touchRightBorder) && (!touchTopBorder)) { // Touches/intersects only the bottom border of the RoI - computeIntersectionsBottomBorderOnly(v_c, vmax_roi, radius, delta_theta); + computeIntersBottomBorder(v_c, vmax_roi, radius, delta_theta); } else if ((!touchBottomBorder) && touchLeftBorder && (!touchRightBorder) && (!touchTopBorder)) { // Touches/intersects only the left border of the RoI - computeIntersectionsLeftBorderOnly(u_c, umin_roi, radius, delta_theta); + computeIntersectionsLeftBorder(u_c, umin_roi, radius, delta_theta); } else if ((!touchBottomBorder) && (!touchLeftBorder) && touchRightBorder && (!touchTopBorder)) { // Touches/intersects only the right border of the RoI - computeIntersectionsRightBorderOnly(u_c, umax_roi, radius, delta_theta); + computeIntersectionsRightBorder(u_c, umax_roi, radius, delta_theta); } else if ((!touchBottomBorder) && (!touchLeftBorder) && (!touchRightBorder) && touchTopBorder) { // Touches/intersects only the top border of the RoI - computeIntersectionsTopBorderOnly(v_c, vmin_roi, radius, delta_theta); + computeIntersectionsTopBorder(v_c, vmin_roi, radius, delta_theta); } else if (touchBottomBorder && touchLeftBorder && (!touchRightBorder) && (!touchTopBorder)) { // Touches/intersects the bottom and left borders of the RoI @@ -966,27 +966,27 @@ float vpImageCircle::computeAngularCoverageInRoI(const vpRect &roi, const float } else if (touchBottomBorder && touchTopBorder && touchLeftBorder && (!touchRightBorder)) { // Touches/intersects the top, left and bottom borders of the RoI - computeIntersectionsTopLeftBottom(u_c, v_c, umin_roi, vmin_roi, vmax_roi, radius, delta_theta); + computeIntersTopLeftBottom(u_c, v_c, umin_roi, vmin_roi, vmax_roi, radius, delta_theta); } else if (touchBottomBorder && touchTopBorder && (!touchLeftBorder) && touchRightBorder) { // Touches/intersects the top, right and bottom borders of the RoI - computeIntersectionsTopRightBottom(u_c, v_c, umax_roi, vmin_roi, vmax_roi, radius, delta_theta); + computeIntersTopRightBottom(u_c, v_c, umax_roi, vmin_roi, vmax_roi, radius, delta_theta); } else if (touchBottomBorder && touchTopBorder && (!touchLeftBorder) && (!touchRightBorder)) { // Touches/intersects the top and bottom borders of the RoI - computeIntersectionsTopBottomOnly(u_c, v_c, vmin_roi, vmax_roi, radius, delta_theta); + computeIntersTopBottomOnly(u_c, v_c, vmin_roi, vmax_roi, radius, delta_theta); } else if ((!touchBottomBorder) && touchTopBorder && touchLeftBorder && touchRightBorder) { // Touches/intersects the top, left and right borders of the RoI - computeIntersectionsLeftRightTop(u_c, v_c, umin_roi, umax_roi, vmin_roi, radius, delta_theta); + computeIntersLeftRightTop(u_c, v_c, umin_roi, umax_roi, vmin_roi, radius, delta_theta); } else if (touchBottomBorder && (!touchTopBorder) && touchLeftBorder && touchRightBorder) { // Touches/intersects the bottom, left and right borders of the RoI - computeIntersectionsLeftRightBottom(u_c, v_c, umin_roi, umax_roi, vmax_roi, radius, delta_theta); + computeIntersLeftRightBottom(u_c, v_c, umin_roi, umax_roi, vmax_roi, radius, delta_theta); } else if (touchLeftBorder && touchRightBorder && (!touchTopBorder) && (!touchBottomBorder)) { // Touches/intersects the bottom, left and right borders of the RoI - computeIntersectionsLeftRightOnly(u_c, v_c, umin_roi, umax_roi, radius, delta_theta); + computeIntersectionsLeftRight(u_c, v_c, umin_roi, umax_roi, radius, delta_theta); } else if (touchLeftBorder && touchRightBorder && touchTopBorder && touchBottomBorder) { // Touches/intersects each axis @@ -1058,7 +1058,7 @@ unsigned int vpImageCircle::computePixelsInMask(const vpImage &mask) const } if (mask[y][x]) { // Increment only if the pixel value of the mask is true - count++; + ++count; } }; #endif @@ -1163,4 +1163,4 @@ float vpImageCircle::get_n02() const float vpImageCircle::get_n11() const { return 0.; -}; +} diff --git a/modules/core/src/image/vpImageFilter.cpp b/modules/core/src/image/vpImageFilter.cpp index 23de0acd44..6658d1f44c 100644 --- a/modules/core/src/image/vpImageFilter.cpp +++ b/modules/core/src/image/vpImageFilter.cpp @@ -114,17 +114,17 @@ vpImageFilter::vpCannyBackendType vpImageFilter::vpCannyBackendTypeFromString(co * \param[in] suf The suffix of the list. * \return std::string The list of available items. */ -std::string vpImageFilter::vpCannyFilteringAndGradientTypeList(const std::string &pref, const std::string &sep, +std::string vpImageFilter::vpGetCannyFiltAndGradTypes(const std::string &pref, const std::string &sep, const std::string &suf) { std::string list(pref); for (unsigned int i = 0; i < (CANNY_COUNT_FILTERING - 1); ++i) { vpCannyFilteringAndGradientType type = static_cast(i); - list += vpCannyFilteringAndGradientTypeToString(type); + list += vpCannyFiltAndGradTypeToStr(type); list += sep; } vpCannyFilteringAndGradientType type = static_cast(CANNY_COUNT_FILTERING - 1); - list += vpCannyFilteringAndGradientTypeToString(type); + list += vpCannyFiltAndGradTypeToStr(type); list += suf; return list; } @@ -135,7 +135,7 @@ std::string vpImageFilter::vpCannyFilteringAndGradientTypeList(const std::string * \param[in] type The type that must be casted into a string. * \return std::string The corresponding name. */ -std::string vpImageFilter::vpCannyFilteringAndGradientTypeToString(const vpImageFilter::vpCannyFilteringAndGradientType &type) +std::string vpImageFilter::vpCannyFiltAndGradTypeToStr(const vpImageFilter::vpCannyFilteringAndGradientType &type) { std::string name; switch (type) { @@ -158,7 +158,7 @@ std::string vpImageFilter::vpCannyFilteringAndGradientTypeToString(const vpImage * \param[in] name The name of the backend. * \return vpImageFilter::vpCannyFilteringAndGradientType The corresponding enumeration value. */ -vpImageFilter::vpCannyFilteringAndGradientType vpImageFilter::vpCannyFilteringAndGradientTypeFromString(const std::string &name) +vpImageFilter::vpCannyFilteringAndGradientType vpImageFilter::vpCannyFiltAndGradTypeFromStr(const std::string &name) { vpCannyFilteringAndGradientType type(CANNY_COUNT_FILTERING); std::string nameLowerCase = vpIoTools::toLowerCase(name); @@ -167,7 +167,7 @@ vpImageFilter::vpCannyFilteringAndGradientType vpImageFilter::vpCannyFilteringAn unsigned int i = 0; while ((i < count) && notFound) { vpCannyFilteringAndGradientType temp = static_cast(i); - if (nameLowerCase == vpCannyFilteringAndGradientTypeToString(temp)) { + if (nameLowerCase == vpCannyFiltAndGradTypeToStr(temp)) { type = temp; notFound = false; } diff --git a/modules/core/src/image/vpImageTools.cpp b/modules/core/src/image/vpImageTools.cpp index 50da489b4f..b4f180d622 100644 --- a/modules/core/src/image/vpImageTools.cpp +++ b/modules/core/src/image/vpImageTools.cpp @@ -1117,9 +1117,10 @@ int vpImageTools::inRange(const unsigned char *hue, const unsigned char *saturat #pragma omp parallel for reduction(+:cpt_in_range) #endif for (int i = 0; i < size_; ++i) { - if ((h_low <= hue[i]) && (hue[i] <= h_high) && - (s_low <= saturation[i]) && (saturation[i] <= s_high) && - (v_low <= value[i]) && (value[i] <= v_high)) { + bool check_h_low_high_hue = (h_low <= hue[i]) && (hue[i] <= h_high); + bool check_s_low_high_saturation = (s_low <= saturation[i]) && (saturation[i] <= s_high); + bool check_v_low_high_value = (v_low <= value[i]) && (value[i] <= v_high); + if (check_h_low_high_hue && check_s_low_high_saturation && check_v_low_high_value) { mask[i] = 255; ++cpt_in_range; } @@ -1170,9 +1171,10 @@ int vpImageTools::inRange(const unsigned char *hue, const unsigned char *saturat #pragma omp parallel for reduction(+:cpt_in_range) #endif for (int i = 0; i < size_; ++i) { - if ((h_low <= hue[i]) && (hue[i] <= h_high) && - (s_low <= saturation[i]) && (saturation[i] <= s_high) && - (v_low <= value[i]) && (value[i] <= v_high)) { + bool check_h_low_high_hue = (h_low <= hue[i]) && (hue[i] <= h_high); + bool check_s_low_high_saturation = (s_low <= saturation[i]) && (saturation[i] <= s_high); + bool check_v_low_high_value = (v_low <= value[i]) && (value[i] <= v_high); + if (check_h_low_high_hue && check_s_low_high_saturation && check_v_low_high_value) { mask[i] = 255; ++cpt_in_range; } diff --git a/modules/core/src/math/matrix/vpColVector.cpp b/modules/core/src/math/matrix/vpColVector.cpp index 8db3b582a0..35157bb1ae 100644 --- a/modules/core/src/math/matrix/vpColVector.cpp +++ b/modules/core/src/math/matrix/vpColVector.cpp @@ -583,15 +583,15 @@ vpColVector vpColVector::invSort(const vpColVector &v) unsigned int i = 0; while (nb_permutation != 0) { nb_permutation = 0; - for (unsigned int j = v.getRows() - 1; j >= (i + 1); j--) { + for (unsigned int j = v.getRows() - 1; j >= (i + 1); --j) { if (tab[j] > tab[j - 1]) { double tmp = tab[j]; tab[j] = tab[j - 1]; tab[j - 1] = tmp; - nb_permutation++; + ++nb_permutation; } } - i++; + ++i; } return tab; @@ -608,15 +608,15 @@ vpColVector vpColVector::sort(const vpColVector &v) unsigned int i = 0; while (nb_permutation != 0) { nb_permutation = 0; - for (unsigned int j = v.getRows() - 1; j >= (i + 1); j--) { + for (unsigned int j = v.getRows() - 1; j >= (i + 1); --j) { if (tab[j] < tab[j - 1]) { double tmp = tab[j]; tab[j] = tab[j - 1]; tab[j - 1] = tmp; - nb_permutation++; + ++nb_permutation; } } - i++; + ++i; } return tab; diff --git a/modules/core/src/math/matrix/vpMatrix.cpp b/modules/core/src/math/matrix/vpMatrix.cpp index 3a6939e1b2..db8fc13027 100644 --- a/modules/core/src/math/matrix/vpMatrix.cpp +++ b/modules/core/src/math/matrix/vpMatrix.cpp @@ -128,8 +128,8 @@ void compute_pseudo_inverse(const vpMatrix &U, const vpColVector &sv, const vpMa unsigned int sv_size = sv.size(); for (unsigned int i = 0; i < sv_size; ++i) { - if (sv[i] > (maxsv * svThreshold)) { - rank_out++; + if (sv[i] >(maxsv * svThreshold)) { + ++rank_out; } } @@ -4999,17 +4999,17 @@ vpColVector vpMatrix::getCol(unsigned int j) const { return getCol(j, 0, rowNum) std::cout << "Row vector: \n" << rv << std::endl; } \endcode - It produces the following output: - \code - [4,4]= - 0 1 2 3 - 4 5 6 7 - 8 9 10 11 - 12 13 14 15 - Row vector: - 4 5 6 7 - \endcode - */ +It produces the following output : +\code +[4, 4] = +0 1 2 3 +4 5 6 7 +8 9 10 11 +12 13 14 15 +Row vector : +4 5 6 7 +\endcode +*/ vpRowVector vpMatrix::getRow(unsigned int i) const { return getRow(i, 0, colNum); } /*! @@ -6088,8 +6088,8 @@ unsigned int vpMatrix::kernel(vpMatrix &kerAt, double svThreshold) const unsigned int rank = 0; for (unsigned int i = 0; i < nbcol; ++i) { - if (sv[i] > (maxsv * svThreshold)) { - rank++; + if (sv[i] >(maxsv * svThreshold)) { + ++rank; } } @@ -6103,7 +6103,7 @@ unsigned int vpMatrix::kernel(vpMatrix &kerAt, double svThreshold) const for (unsigned int i = 0; i < v_rows; ++i) { kerAt[k][i] = V[i][j]; } - k++; + ++k; } } } @@ -6157,8 +6157,8 @@ unsigned int vpMatrix::nullSpace(vpMatrix &kerA, double svThreshold) const unsigned int rank = 0; for (unsigned int i = 0; i < nbcol; ++i) { - if (sv[i] > (maxsv * svThreshold)) { - rank++; + if (sv[i] >(maxsv * svThreshold)) { + ++rank; } } @@ -6170,7 +6170,7 @@ unsigned int vpMatrix::nullSpace(vpMatrix &kerA, double svThreshold) const for (unsigned int i = 0; i < nbcol; ++i) { kerA[i][k] = V[i][j]; } - k++; + ++k; } } } @@ -6234,8 +6234,8 @@ unsigned int vpMatrix::nullSpace(vpMatrix &kerA, int dim) const double maxsv = sv[0]; unsigned int rank = 0; for (unsigned int i = 0; i < nbcol; ++i) { - if (sv[i] > (maxsv * 1e-6)) { - rank++; + if (sv[i] >(maxsv * 1e-6)) { + ++rank; } } return (nbcol - rank); @@ -6463,8 +6463,8 @@ double vpMatrix::cond(double svThreshold) const // Compute the rank of the matrix unsigned int rank = 0; for (unsigned int i = 0; i < nbcol; ++i) { - if (sv[i] > (maxsv * svThreshold)) { - rank++; + if (sv[i] >(maxsv * svThreshold)) { + ++rank; } } diff --git a/modules/core/src/math/robust/vpRobust.cpp b/modules/core/src/math/robust/vpRobust.cpp index abbadffc39..c781df403b 100644 --- a/modules/core/src/math/robust/vpRobust.cpp +++ b/modules/core/src/math/robust/vpRobust.cpp @@ -274,10 +274,12 @@ int vpRobust::partition(vpColVector &a, int l, int r) while (a[++i] < v) ; while (v < a[--j]) - if (j == l) + if (j == l) { break; - if (i >= j) + } + if (i >= j) { break; + } std::swap(a[i], a[j]); } std::swap(a[i], a[r]); diff --git a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp index 2a1d7f50c7..c9c8ed4099 100644 --- a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp +++ b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp @@ -739,7 +739,7 @@ int main() */ vpHomogeneousMatrix &vpHomogeneousMatrix::operator,(double val) { - m_index++; + ++m_index; if (m_index >= size()) { throw(vpException(vpException::dimensionError, "Cannot set homogenous matrix out of bounds. It has only %d elements while you try to initialize " diff --git a/modules/core/src/math/transformation/vpRotationMatrix.cpp b/modules/core/src/math/transformation/vpRotationMatrix.cpp index 008430201b..9d0714c22a 100644 --- a/modules/core/src/math/transformation/vpRotationMatrix.cpp +++ b/modules/core/src/math/transformation/vpRotationMatrix.cpp @@ -240,7 +240,7 @@ int main() */ vpRotationMatrix &vpRotationMatrix::operator,(double val) { - m_index++; + ++m_index; if (m_index >= size()) { throw(vpException(vpException::dimensionError, "Cannot set rotation matrix out of bounds. It has only %d elements while you try to initialize " diff --git a/modules/core/src/math/transformation/vpThetaUVector.cpp b/modules/core/src/math/transformation/vpThetaUVector.cpp index 7d61de8150..507f2c9dab 100644 --- a/modules/core/src/math/transformation/vpThetaUVector.cpp +++ b/modules/core/src/math/transformation/vpThetaUVector.cpp @@ -380,7 +380,7 @@ void vpThetaUVector::extract(double &theta, vpColVector &u) const u.resize(3); theta = getTheta(); - // --comment: if (theta == 0) + // --comment: if theta equals 0 if (std::fabs(theta) <= std::numeric_limits::epsilon()) { u = 0; return; @@ -478,7 +478,7 @@ vpThetaUVector vpThetaUVector::operator*(const vpThetaUVector &tu_b) const vpColVector b_hat_sin_2 = b_hat * std::sin(b_2); double c = 2 * std::acos((std::cos(a_2) * std::cos(b_2)) - (vpColVector::dotProd(a_hat_sin_2, b_hat_sin_2))); vpColVector d = ((std::sin(a_2) * std::cos(b_2) * a_hat) + (std::cos(a_2) * std::sin(b_2) * b_hat)) + - std::sin(a_2) * std::sin(b_2) * vpColVector::crossProd(a_hat, b_hat); + (std::sin(a_2) * std::sin(b_2) * vpColVector::crossProd(a_hat, b_hat)); d = (c * d) / std::sin(c / 2); return vpThetaUVector(d); diff --git a/modules/core/src/math/transformation/vpTranslationVector.cpp b/modules/core/src/math/transformation/vpTranslationVector.cpp index a59f5530e8..bc5196c591 100644 --- a/modules/core/src/math/transformation/vpTranslationVector.cpp +++ b/modules/core/src/math/transformation/vpTranslationVector.cpp @@ -598,7 +598,7 @@ vpTranslationVector &vpTranslationVector::operator<<(double val) */ vpTranslationVector &vpTranslationVector::operator,(double val) { - m_index++; + ++m_index; if (m_index >= size()) { throw(vpException( vpException::dimensionError, diff --git a/modules/core/src/math/transformation/vpVelocityTwistMatrix.cpp b/modules/core/src/math/transformation/vpVelocityTwistMatrix.cpp index c2ba8f4a66..cf6c8e0daa 100644 --- a/modules/core/src/math/transformation/vpVelocityTwistMatrix.cpp +++ b/modules/core/src/math/transformation/vpVelocityTwistMatrix.cpp @@ -527,7 +527,7 @@ int vpVelocityTwistMatrix::print(std::ostream &s, unsigned int length, char cons std::ostringstream ossFixed; std::ios_base::fmtflags original_flags = oss.flags(); - // --comment: ossFixed < @@ -247,6 +248,7 @@ bool vpRect::operator!=(const vpRect &r) const // --comment: std::fabs(width)*std::numeric_limits::epsilon() // --comment: || std::fabs(height-r.height) > // --comment: std::fabs(height)*std::numeric_limits::epsilon() + */ return !(*this == r); } diff --git a/modules/core/src/tools/histogram/vpHistogram.cpp b/modules/core/src/tools/histogram/vpHistogram.cpp index aca247a683..ff93dc2f48 100644 --- a/modules/core/src/tools/histogram/vpHistogram.cpp +++ b/modules/core/src/tools/histogram/vpHistogram.cpp @@ -451,7 +451,7 @@ void vpHistogram::equalize(const vpImage &I, vpImage(nbPixels - cdfMin) * 255.0); + lut[x] = vpMath::round(((cdf[x] - cdfMin) / static_cast(nbPixels - cdfMin)) * 255.0); } Iout = I; @@ -589,24 +589,25 @@ unsigned vpHistogram::getPeaks(std::list &peaks) if ((prev_slope > 0) && (next_slope == 0)) { sum_level += i + 1; ++cpt; - continue; + // continue; } + else { + // Peak detection + if ((prev_slope > 0) && (next_slope < 0)) { + sum_level += i; + ++cpt; - // Peak detection - if ((prev_slope > 0) && (next_slope < 0)) { - sum_level += i; - ++cpt; + unsigned int level = sum_level / cpt; + p.set(static_cast(level), m_histogram[level]); + peaks.push_back(p); - unsigned int level = sum_level / cpt; - p.set(static_cast(level), m_histogram[level]); - peaks.push_back(p); + ++nbpeaks; + } - ++nbpeaks; + prev_slope = next_slope; + sum_level = 0; + cpt = 0; } - - prev_slope = next_slope; - sum_level = 0; - cpt = 0; } if (prev_slope > 0) { p.set(static_cast(m_size) - 1u, m_histogram[m_size - 1]); @@ -713,14 +714,16 @@ bool vpHistogram::getPeaks(unsigned char dist, vpHistogramPeak &peakl, vpHistogr for (unsigned i = 0; i < (m_size - 1); ++i) { int next_slope = static_cast(m_histogram[i + 1]) - static_cast(m_histogram[i]); // Next histogram inclination if (next_slope == 0) { - continue; + // continue } + else { // Peak detection - if ((prev_slope > 0) && (next_slope < 0)) { - peak[nbpeaks++] = static_cast(i); - } + if ((prev_slope > 0) && (next_slope < 0)) { + peak[nbpeaks++] = static_cast(i); + } - prev_slope = next_slope; + prev_slope = next_slope; + } } if (prev_slope > 0) { peak[nbpeaks++] = static_cast(m_size - 1); @@ -798,11 +801,13 @@ bool vpHistogram::getPeaks(unsigned char dist, vpHistogramPeak &peakl, vpHistogr mini = m_histogram[i]; nbmini = 1; sumindmini = i; - continue; + // continue } - if (m_histogram[i] == mini) { - sumindmini += i; - ++nbmini; + else { + if (m_histogram[i] == mini) { + sumindmini += i; + ++nbmini; + } } } @@ -860,24 +865,25 @@ unsigned vpHistogram::getValey(std::list &valey) if ((prev_slope < 0) && (next_slope == 0)) { sum_level += i + 1; ++cpt; - continue; + // continue } - + else { // Valey detection - if ((prev_slope < 0) && (next_slope > 0)) { - sum_level += i; - ++cpt; + if ((prev_slope < 0) && (next_slope > 0)) { + sum_level += i; + ++cpt; - unsigned int level = sum_level / cpt; - p.set(static_cast(level), m_histogram[level]); - valey.push_back(p); + unsigned int level = sum_level / cpt; + p.set(static_cast(level), m_histogram[level]); + valey.push_back(p); - ++nbvaley; - } + ++nbvaley; + } - prev_slope = next_slope; - sum_level = 0; - cpt = 0; + prev_slope = next_slope; + sum_level = 0; + cpt = 0; + } } if (prev_slope < 0) { p.set(static_cast(m_size) - 1u, m_histogram[m_size - 1]); @@ -930,11 +936,13 @@ bool vpHistogram::getValey(const vpHistogramPeak &peak1, const vpHistogramPeak & mini = m_histogram[i]; nbmini = 1; sumindmini = i; - continue; + // continue } - if (m_histogram[i] == mini) { - sumindmini += i; - ++nbmini; + else { + if (m_histogram[i] == mini) { + sumindmini += i; + ++nbmini; + } } } @@ -1041,11 +1049,13 @@ unsigned vpHistogram::getValey(unsigned char dist, const vpHistogramPeak &peak, mini = m_histogram[i]; nbmini = 1; sumindmini = i; - continue; + // continue } - if (m_histogram[i] == mini) { - sumindmini += i; - ++nbmini; + else { + if (m_histogram[i] == mini) { + sumindmini += i; + ++nbmini; + } } } if (nbmini == 0) { @@ -1102,11 +1112,13 @@ unsigned vpHistogram::getValey(unsigned char dist, const vpHistogramPeak &peak, mini = m_histogram[i]; nbmini = 1; sumindmini = i; - continue; + // continue } - if (m_histogram[i] == mini) { - sumindmini += i; - ++nbmini; + else { + if (m_histogram[i] == mini) { + sumindmini += i; + ++nbmini; + } } } if (nbmini == 0) { diff --git a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h index d2c489b60a..d51df0d51c 100644 --- a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h +++ b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h @@ -454,7 +454,7 @@ class VISP_EXPORT vpCircleHoughTransform { std::stringstream txt; txt << "Hough Circle Transform Configuration:\n"; - txt << "\tFiltering + gradient operators = " << vpImageFilter::vpCannyFilteringAndGradientTypeToString(m_filteringAndGradientType) << "\n"; + txt << "\tFiltering + gradient operators = " << vpImageFilter::vpCannyFiltAndGradTypeToStr(m_filteringAndGradientType) << "\n"; txt << "\tGaussian filter kernel size = " << m_gaussianKernelSize << "\n"; txt << "\tGaussian filter standard deviation = " << m_gaussianStdev << "\n"; txt << "\tGradient filter kernel size = " << m_gradientFilterKernelSize << "\n"; @@ -545,9 +545,9 @@ class VISP_EXPORT vpCircleHoughTransform */ friend inline void from_json(const nlohmann::json &j, vpCircleHoughTransformParameters ¶ms) { - std::string filteringAndGradientName = vpImageFilter::vpCannyFilteringAndGradientTypeToString(params.m_filteringAndGradientType); + std::string filteringAndGradientName = vpImageFilter::vpCannyFiltAndGradTypeToStr(params.m_filteringAndGradientType); filteringAndGradientName = j.value("filteringAndGradientType", filteringAndGradientName); - params.m_filteringAndGradientType = vpImageFilter::vpCannyFilteringAndGradientTypeFromString(filteringAndGradientName); + params.m_filteringAndGradientType = vpImageFilter::vpCannyFiltAndGradTypeFromStr(filteringAndGradientName); params.m_gaussianKernelSize = j.value("gaussianKernelSize", params.m_gaussianKernelSize); if ((params.m_gaussianKernelSize % 2) != 1) { @@ -626,7 +626,7 @@ class VISP_EXPORT vpCircleHoughTransform std::pair radiusLimits = { params.m_minRadius, params.m_maxRadius }; j = nlohmann::json { - {"filteringAndGradientType", vpImageFilter::vpCannyFilteringAndGradientTypeToString(params.m_filteringAndGradientType)}, + {"filteringAndGradientType", vpImageFilter::vpCannyFiltAndGradTypeToStr(params.m_filteringAndGradientType)}, {"gaussianKernelSize", params.m_gaussianKernelSize}, {"gaussianStdev", params.m_gaussianStdev}, {"gradientFilterKernelSize", params.m_gradientFilterKernelSize}, diff --git a/modules/imgproc/src/vpCLAHE.cpp b/modules/imgproc/src/vpCLAHE.cpp index 7f6b9f4be2..5bea19d052 100644 --- a/modules/imgproc/src/vpCLAHE.cpp +++ b/modules/imgproc/src/vpCLAHE.cpp @@ -165,7 +165,7 @@ float transferValue(int v, std::vector &clippedHist) { int clippedHistLength = static_cast(clippedHist.size()); int hMin = clippedHistLength - 1; - for (int i = 0; i < hMin; ++i) { + for (int i = 0; i &I1, vpImage &I2, int blo t1 = (wx * t10) + ((1.0f - wx) * t11); } - float t = (r0 == r1) ? t0 : (wy * t0) + ((1.0f - wy) * t1); + float t = (r0 == r1) ? t0 : ((wy * t0) + ((1.0f - wy) * t1)); I2[y][x] = std::max(0, std::min(255, fastRound(t * 255.0f))); } } @@ -435,7 +435,7 @@ void clahe(const vpImage &I1, vpImage &I2, int blo int v = fastRound((I1[y][x] / 255.0f) * bins); int w = std::min(static_cast(I1.getWidth()), xMax) - xMin; int n = h * w; - int limit = static_cast((slope * n) / bins + 0.5f); + int limit = static_cast(((slope * n) / bins) + 0.5f); I2[y][x] = fastRound(transferValue(v, hist, clippedHist, limit) * 255.0f); } } @@ -460,7 +460,7 @@ void clahe(const vpImage &I1, vpImage &I2, int blockRadius, int I2.resize(I1.getHeight(), I1.getWidth()); unsigned int size = I2.getWidth() * I2.getHeight(); - unsigned char *ptrStart = (unsigned char *)(I2.bitmap); + unsigned char *ptrStart = reinterpret_cast(I2.bitmap); unsigned char *ptrEnd = ptrStart + (size * 4); unsigned char *ptrCurrent = ptrStart; diff --git a/modules/imgproc/src/vpCircleHoughTransform.cpp b/modules/imgproc/src/vpCircleHoughTransform.cpp index a4f62b694c..e88fa70ff7 100644 --- a/modules/imgproc/src/vpCircleHoughTransform.cpp +++ b/modules/imgproc/src/vpCircleHoughTransform.cpp @@ -212,7 +212,7 @@ vpCircleHoughTransform::initGradientFilters() } else { std::string errMsg = "[vpCircleHoughTransform::initGradientFilters] Error: gradient filtering method \""; - errMsg += vpImageFilter::vpCannyFilteringAndGradientTypeToString(m_algoParams.m_filteringAndGradientType); + errMsg += vpImageFilter::vpCannyFiltAndGradTypeToStr(m_algoParams.m_filteringAndGradientType); errMsg += "\" has not been implemented yet\n"; throw vpException(vpException::notImplementedError, errMsg); } @@ -453,7 +453,7 @@ vpCircleHoughTransform::computeGradients(const vpImage &I) } else { std::string errMsg("[computeGradients] The filtering + gradient operators \""); - errMsg += vpImageFilter::vpCannyFilteringAndGradientTypeToString(m_algoParams.m_filteringAndGradientType); + errMsg += vpImageFilter::vpCannyFiltAndGradTypeToStr(m_algoParams.m_filteringAndGradientType); errMsg += "\" is not implemented (yet)."; throw(vpException(vpException::notImplementedError, errMsg)); } diff --git a/modules/imgproc/src/vpContours.cpp b/modules/imgproc/src/vpContours.cpp index 530f99b96a..b982b3669b 100644 --- a/modules/imgproc/src/vpContours.cpp +++ b/modules/imgproc/src/vpContours.cpp @@ -158,15 +158,18 @@ void followBorder(vpImage &I, const vpImagePoint &ij, vpImagePoint &i2j2, v vpImagePoint i1j1(-1, -1); // --comment: find i1j1 3.1 - while (trace.m_direction != dir.m_direction) { + bool activepixel_ij_neg = true; + while ((trace.m_direction != dir.m_direction) && activepixel_ij_neg) { vpImagePoint activePixel = trace.active(I, ij); if ((activePixel.get_i() >= 0) && (activePixel.get_j() >= 0)) { i1j1 = activePixel; - break; + activepixel_ij_neg = false; + // break + } + else { + trace = trace.clockwise(); } - - trace = trace.clockwise(); } if ((i1j1.get_i() < 0) || (i1j1.get_j() < 0)) { @@ -179,7 +182,8 @@ void followBorder(vpImage &I, const vpImagePoint &ij, vpImagePoint &i2j2, v bool checked[8] = { false, false, false, false, false, false, false, false }; - while (true) { + bool i4j4_eq_ij_and_i3j3_eq_i1j1 = false; + while (i4j4_eq_ij_and_i3j3_eq_i1j1 == false) { if (!fromTo(i3j3, i2j2, dir)) { throw vpException(vpException::fatalError, "i3j3 == i2j2"); } @@ -192,26 +196,31 @@ void followBorder(vpImage &I, const vpImagePoint &ij, vpImagePoint &i2j2, v checked[cpt] = false; } - while (true) { + bool i4j4_ij_neg = true; + while (true && i4j4_ij_neg) { i4j4 = trace.active(I, i3j3); //(3.3) if ((i4j4.get_i() >= 0) && (i4j4.get_j() >= 0)) { - break; + i4j4_ij_neg = false; + //break + } + else { + checked[static_cast(trace.m_direction)] = true; + trace = trace.counterClockwise(); } - - checked[static_cast(trace.m_direction)] = true; - trace = trace.counterClockwise(); } addContourPoint(I, border, i3j3, checked, nbd); if ((i4j4 == ij) && (i3j3 == i1j1)) { //(3.5) - break; + i4j4_eq_ij_and_i3j3_eq_i1j1 = true; + // break + } + else { + //(3.5) + i2j2 = i3j3; + i3j3 = i4j4; } - - //(3.5) - i2j2 = i3j3; - i3j3 = i4j4; } } diff --git a/modules/imgproc/src/vpImgproc.cpp b/modules/imgproc/src/vpImgproc.cpp index 762170f012..ff25389262 100644 --- a/modules/imgproc/src/vpImgproc.cpp +++ b/modules/imgproc/src/vpImgproc.cpp @@ -258,7 +258,7 @@ void equalizeHistogram(vpImage &I, bool useHSV) // Merge the result in I unsigned int size = I.getWidth() * I.getHeight(); - unsigned char *ptrStart = (unsigned char *)I.bitmap; + unsigned char *ptrStart = reinterpret_cast(I.bitmap); unsigned char *ptrEnd = ptrStart + (size * 4); unsigned char *ptrCurrent = ptrStart; @@ -286,15 +286,15 @@ void equalizeHistogram(vpImage &I, bool useHSV) unsigned int size = I.getWidth() * I.getHeight(); // Convert from RGBa to HSV - vpImageConvert::RGBaToHSV((unsigned char *)I.bitmap, (unsigned char *)hue.bitmap, - (unsigned char *)saturation.bitmap, (unsigned char *)value.bitmap, size); + vpImageConvert::RGBaToHSV(reinterpret_cast(I.bitmap), reinterpret_cast(hue.bitmap), + reinterpret_cast(saturation.bitmap), reinterpret_cast(value.bitmap), size); // Histogram equalization on the value plane vp::equalizeHistogram(value); // Convert from HSV to RGBa - vpImageConvert::HSVToRGBa((unsigned char *)hue.bitmap, (unsigned char *)saturation.bitmap, - (unsigned char *)value.bitmap, (unsigned char *)I.bitmap, size); + vpImageConvert::HSVToRGBa(reinterpret_cast(hue.bitmap), reinterpret_cast(saturation.bitmap), + reinterpret_cast(value.bitmap), reinterpret_cast(I.bitmap), size); } } @@ -667,14 +667,14 @@ void gammaCorrection(vpImage &I, const float &gamma, const vpGammaColorH std::vector saturation(size); std::vector value(size); - vpImageConvert::RGBaToHSV((unsigned char *)I.bitmap, &hue.front(), &saturation.front(), &value.front(), size); + vpImageConvert::RGBaToHSV(reinterpret_cast(I.bitmap), &hue.front(), &saturation.front(), &value.front(), size); vpImage I_hue(&hue.front(), height, width); vpImage I_saturation(&saturation.front(), height, width); vpImage I_value(&value.front(), height, width); gammaCorrection(I_value, gamma, method, p_mask); - vpImageConvert::HSVToRGBa(I_hue.bitmap, I_saturation.bitmap, I_value.bitmap, (unsigned char *)I.bitmap, size); + vpImageConvert::HSVToRGBa(I_hue.bitmap, I_saturation.bitmap, I_value.bitmap, reinterpret_cast(I.bitmap), size); } else if (colorHandling == GAMMA_RGB) { vpImage pR, pG, pB, pa; @@ -820,7 +820,7 @@ void stretchContrastHSV(vpImage &I) // Convert RGB to HSV vpImage hueImage(I.getHeight(), I.getWidth()), saturationImage(I.getHeight(), I.getWidth()), valueImage(I.getHeight(), I.getWidth()); - vpImageConvert::RGBaToHSV((unsigned char *)I.bitmap, hueImage.bitmap, saturationImage.bitmap, valueImage.bitmap, + vpImageConvert::RGBaToHSV(reinterpret_cast(I.bitmap), hueImage.bitmap, saturationImage.bitmap, valueImage.bitmap, size); // Find min and max Saturation and Value @@ -853,7 +853,7 @@ void stretchContrastHSV(vpImage &I) } // Convert HSV to RGBa - vpImageConvert::HSVToRGBa(hueImage.bitmap, saturationImage.bitmap, valueImage.bitmap, (unsigned char *)(I.bitmap), + vpImageConvert::HSVToRGBa(hueImage.bitmap, saturationImage.bitmap, valueImage.bitmap, reinterpret_cast(I.bitmap), size); } diff --git a/modules/imgproc/src/vpMorph.cpp b/modules/imgproc/src/vpMorph.cpp index c3d0435a87..f00b686d31 100644 --- a/modules/imgproc/src/vpMorph.cpp +++ b/modules/imgproc/src/vpMorph.cpp @@ -136,6 +136,7 @@ void reconstruct(const vpImage &marker, const vpImage h_k = marker; h_kp1 = h_k; + bool h_kp1_eq_h_k = false; do { // Dilatation vpImageMorphology::dilatation(h_kp1, connexity); @@ -150,10 +151,12 @@ void reconstruct(const vpImage &marker, const vpImage::epsilon())) { - continue; - } - - w_F = static_cast(imageSize) - w_B; - if (vpMath::nul(w_F, std::numeric_limits::epsilon())) { - break; - } - - // Mean Background / Foreground - float mu_B = sum_ip_all[cpt] / static_cast(w_B); - float mu_F = (mu_T - sum_ip_all[cpt]) / static_cast(w_F); - // If there is a case where (w_B * w_F) exceed FLT_MAX, normalize - // histogram - float sigma_b_sqr = w_B * w_F * (mu_B - mu_F) * (mu_B - mu_F); - - if (sigma_b_sqr >= max_sigma_b) { - threshold = cpt; - max_sigma_b = sigma_b_sqr; + bool w_b_eq_nul = vpMath::nul(w_B, std::numeric_limits::epsilon()); + if (w_b_eq_nul == false) { + + w_F = static_cast(imageSize) - w_B; + w_f_eq_nul = vpMath::nul(w_F, std::numeric_limits::epsilon()); + if (w_f_eq_nul == false) { + + // Mean Background / Foreground + float mu_B = sum_ip_all[cpt] / static_cast(w_B); + float mu_F = (mu_T - sum_ip_all[cpt]) / static_cast(w_F); + // If there is a case where (w_B * w_F) exceed FLT_MAX, normalize + // histogram + float sigma_b_sqr = w_B * w_F * (mu_B - mu_F) * (mu_B - mu_F); + + if (sigma_b_sqr >= max_sigma_b) { + threshold = cpt; + max_sigma_b = sigma_b_sqr; + } + } + // else exit the loop } } @@ -318,8 +320,8 @@ int computeThresholdTriangle(vpHistogram &hist) } // First / last index when hist(cpt) == 0 - left_bound = left_bound > 0 ? left_bound - 1 : left_bound; - right_bound = right_bound < static_cast(hist.getSize()) - 1 ? right_bound + 1 : right_bound; + left_bound = left_bound > 0 ? (left_bound - 1) : left_bound; + right_bound = right_bound < (static_cast(hist.getSize()) - 1) ? (right_bound + 1) : right_bound; // Use the largest bound bool flip = false; diff --git a/modules/tracker/blob/include/visp3/blob/vpDot2.h b/modules/tracker/blob/include/visp3/blob/vpDot2.h index 2e3c4b1130..128108d445 100644 --- a/modules/tracker/blob/include/visp3/blob/vpDot2.h +++ b/modules/tracker/blob/include/visp3/blob/vpDot2.h @@ -221,7 +221,7 @@ class VISP_EXPORT vpDot2 : public vpTracker double getGrayLevelPrecision() const; double getHeight() const; - double getMaxSizeSearchDistancePrecision() const; + double getMaxSizeSearchDistPrecision() const; /*! * \return The mean gray level value of the dot. @@ -345,15 +345,17 @@ class VISP_EXPORT vpDot2 : public vpTracker */ inline void setGrayLevelMax(const unsigned int &max) { - if (max > 255) + if (max > 255) { this->gray_level_max = 255; - else + } + else { this->gray_level_max = max; + } }; void setGrayLevelPrecision(const double &grayLevelPrecision); void setHeight(const double &height); - void setMaxSizeSearchDistancePrecision(const double &maxSizeSearchDistancePrecision); + void setMaxSizeSearchDistPrecision(const double &maxSizeSearchDistancePrecision); void setSizePrecision(const double &sizePrecision); void setWidth(const double &width); diff --git a/modules/tracker/blob/src/dots/vpDot2.cpp b/modules/tracker/blob/src/dots/vpDot2.cpp index fe9f9ed377..d4118dcc55 100644 --- a/modules/tracker/blob/src/dots/vpDot2.cpp +++ b/modules/tracker/blob/src/dots/vpDot2.cpp @@ -647,7 +647,7 @@ double vpDot2::getEllipsoidShapePrecision() const { return ellipsoidShapePrecisi [0.05,1]. 1 means full precision, whereas values close to 0 show a very bad precision. */ -double vpDot2::getMaxSizeSearchDistancePrecision() const { return maxSizeSearchDistancePrecision; } +double vpDot2::getMaxSizeSearchDistPrecision() const { return maxSizeSearchDistancePrecision; } /*! Return the distance between the two center of dots. @@ -818,7 +818,7 @@ void vpDot2::setEllipsoidShapePrecision(const double &precision) - Values higher than 1 are brought back to 1. */ -void vpDot2::setMaxSizeSearchDistancePrecision(const double &precision) +void vpDot2::setMaxSizeSearchDistPrecision(const double &precision) { double epsilon = 0.05; if (maxSizeSearchDistancePrecision < epsilon) { @@ -1320,6 +1320,7 @@ bool vpDot2::isValid(const vpImage &I, const vpDot2 &wantedDot) if ((std::fabs(ellipsoidShape_precision) > std::numeric_limits::epsilon()) && compute_moment) { // Chaumette, Image Moments: A General and Useful Set of Features for Visual Servoing, TRO 2004, eq 15 + /* // -comment: mu11 = m11 - m00 * xg * yg = m11 - m00 * m10/m00 * m01/m00 // -comment: = m11 - m10 * m01 / m00 // -comment: mu20 = m20 - m00 * xg^2 = m20 - m00 * m10/m00 * m10/m00 @@ -1330,7 +1331,7 @@ bool vpDot2::isValid(const vpImage &I, const vpDot2 &wantedDot) // -comment: a1^2 = 2 / m00 * (mu02 + mu20 + sqrt( (mu20 - mu02)^2 + 4mu11^2) ) // // -comment: a2^2 = 2 / m00 * (mu02 + mu20 - sqrt( (mu20 - mu02)^2 + 4mu11^2) ) - + */ // we compute parameters of the estimated ellipse double tmp1 = (((m01 * m01) - (m10 * m10)) / m00) + (m20 - m02); double tmp2 = m11 - ((m10 * m01) / m00); @@ -1400,22 +1401,24 @@ bool vpDot2::isValid(const vpImage &I, const vpDot2 &wantedDot) (static_cast(u) > area.getRight()) || (static_cast(v) < area.getTop()) || (static_cast(v) > area.getBottom())) { - continue; + // continue } - if (!this->hasReverseLevel(I, u, v)) { + else { + if (!this->hasReverseLevel(I, u, v)) { #ifdef DEBUG - printf("Outside circle pixel (%u, %u) has bad level for dot (%g, " - "%g): %d not in [%u, %u]\n", - u, v, cog_u, cog_v, I[v][u], gray_level_min, gray_level_max); + printf("Outside circle pixel (%u, %u) has bad level for dot (%g, " + "%g): %d not in [%u, %u]\n", + u, v, cog_u, cog_v, I[v][u], gray_level_min, gray_level_max); #endif - ++nb_bad_points; - } - if (graphics) { - for (unsigned int t = 0; t < thickness; ++t) { - ip.set_u(u + t); - ip.set_v(v); + ++nb_bad_points; + } + if (graphics) { + for (unsigned int t = 0; t < thickness; ++t) { + ip.set_u(u + t); + ip.set_v(v); - vpDisplay::displayPoint(I, ip, vpColor::green); + vpDisplay::displayPoint(I, ip, vpColor::green); + } } } } @@ -1783,7 +1786,7 @@ bool vpDot2::findFirstBorder(const vpImage &I, const unsigned int // if the width of this dot was initialised and we already crossed the dot // on more than the max possible width, no need to continue, return an // error tracking - if ((getWidth() > 0) && ((border_u - u) > ((getWidth() / getMaxSizeSearchDistancePrecision()) + epsilon))) { + if ((getWidth() > 0) && ((border_u - u) > ((getWidth() / getMaxSizeSearchDistPrecision()) + epsilon))) { vpDEBUG_TRACE(3, "The found dot (%d, %d, %d) has a greater width than the " "required one", @@ -2198,8 +2201,8 @@ void vpDot2::getGridSize(unsigned int &gridWidth, unsigned int &gridHeight) // contained in the dot. We gent this here if the dot is a perfect disc. // More accurate criterium to define the grid should be implemented if // necessary - gridWidth = static_cast((getWidth() * getMaxSizeSearchDistancePrecision()) / sqrt(2.)); - gridHeight = static_cast((getHeight() * getMaxSizeSearchDistancePrecision()) / sqrt(2.0)); + gridWidth = static_cast((getWidth() * getMaxSizeSearchDistPrecision()) / sqrt(2.)); + gridHeight = static_cast((getHeight() * getMaxSizeSearchDistPrecision()) / sqrt(2.0)); if (gridWidth == 0) { gridWidth = 1; diff --git a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp index 32ec76a377..46fbc3896a 100644 --- a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp @@ -617,7 +617,7 @@ void vpMeEllipse::leastSquare(const vpImage &I, const std::vector // A circle is a particular ellipse. Going from x for circle to K for ellipse // using inverse normalization to go back to pixel values double ratio = vm / um; - m_K[0] = (m_K[1] = 1.0 / (um * um)); + m_K[0] = (m_K[1] = (1.0 / (um * um))); m_K[2] = 0.0; m_K[3] = -(1.0 + (x[0] / 2.0)) / um; m_K[4] = -(ratio + (x[1] / 2.0)) / um; @@ -746,7 +746,7 @@ unsigned int vpMeEllipse::leastSquareRobust(const vpImage &I) // A circle is a particular ellipse. Going from x for circle to K for ellipse // using inverse normalization to go back to pixel values double ratio = vm / um; - m_K[0] = (m_K[1] = 1.0 / (um * um)); + m_K[0] = (m_K[1] = (1.0 / (um * um))); m_K[2] = 0.0; m_K[3] = -(1.0 + (x[0] / 2.0)) / um; m_K[4] = -(ratio + (x[1] / 2.0)) / um; diff --git a/modules/vision/include/visp3/vision/vpPose.h b/modules/vision/include/visp3/vision/vpPose.h index db4e32dfc3..83bbfbfd5f 100644 --- a/modules/vision/include/visp3/vision/vpPose.h +++ b/modules/vision/include/visp3/vision/vpPose.h @@ -354,7 +354,7 @@ class VISP_EXPORT vpPose /*! * Set distance threshold to consider that when a point belongs to a plane. */ - void setDistanceToPlaneForCoplanarityTest(double d); + void setDistToPlaneForCoplanTest(double d); /*! * Set virtual visual servoing gain. diff --git a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp index ed70e010df..a6e091c56e 100644 --- a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp +++ b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp @@ -777,7 +777,7 @@ int lmder(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, double *jac, (*ptr_fcn)(m, n, x, fvec, fjac, ldfjac, iflag); - (*njev)++; + ++(*njev); if (iflag < 0) { /* @@ -983,7 +983,7 @@ int lmder(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, double *jac, iflag = 1; (*ptr_fcn)(m, n, wa2, wa4, fjac, ldfjac, iflag); - (*nfev)++; + ++(*nfev); if (iflag < 0) { // termination, normal ou imposee par l'utilisateur. diff --git a/modules/vision/src/pose-estimation/vpPose.cpp b/modules/vision/src/pose-estimation/vpPose.cpp index feebc4522c..10ecac0f53 100644 --- a/modules/vision/src/pose-estimation/vpPose.cpp +++ b/modules/vision/src/pose-estimation/vpPose.cpp @@ -104,7 +104,7 @@ void vpPose::addPoints(const std::vector &lP) npt = static_cast(listP.size()); } -void vpPose::setDistanceToPlaneForCoplanarityTest(double d) { distanceToPlaneForCoplanarityTest = d; } +void vpPose::setDistToPlaneForCoplanTest(double d) { distanceToPlaneForCoplanarityTest = d; } void vpPose::setDementhonSvThreshold(const double &svThresh) { @@ -252,7 +252,8 @@ bool vpPose::coplanar(int &coplanar_plane_type, double *p_a, double *p_b, double double D = sqrt(vpMath::sqr(a) + vpMath::sqr(b) + vpMath::sqr(c)); - for (it = shuffled_listP.begin(); it != shuffled_listP.end(); ++it) { + std::vector::const_iterator shuffled_listp_end_decl2 = shuffled_listP.end(); + for (it = shuffled_listP.begin(); it != shuffled_listp_end_decl2; ++it) { P1 = *it; double dist = ((a * P1.get_oX()) + (b * P1.get_oY()) + (c * P1.get_oZ()) + d) / D; diff --git a/modules/vision/src/pose-estimation/vpPoseDementhon.cpp b/modules/vision/src/pose-estimation/vpPoseDementhon.cpp index 5429c651c2..cfa8763aeb 100644 --- a/modules/vision/src/pose-estimation/vpPoseDementhon.cpp +++ b/modules/vision/src/pose-estimation/vpPoseDementhon.cpp @@ -437,7 +437,8 @@ void vpPose::poseDementhonPlan(vpHomogeneousMatrix &cMo) cdg[0] = 0.0; cdg[1] = 0.0; cdg[2] = 0.0; - for (std::list::const_iterator it = listP.begin(); it != listP.end(); ++it) { + std::list::const_iterator listp_end = listP.end(); + for (std::list::const_iterator it = listP.begin(); it != listp_end; ++it) { P = (*it); cdg[0] += P.get_oX(); cdg[1] += P.get_oY(); @@ -450,8 +451,8 @@ void vpPose::poseDementhonPlan(vpHomogeneousMatrix &cMo) c3d.clear(); /* translate the 3D points wrt cog */ - std::list::const_iterator listp_end = listP.end(); - for (std::list::const_iterator it = listP.begin(); it != listp_end; ++it) { + std::list::const_iterator listp_end_decl2 = listP.end(); + for (std::list::const_iterator it = listP.begin(); it != listp_end_decl2; ++it) { P = (*it); P.set_oX(P.get_oX() - cdg[0]); P.set_oY(P.get_oY() - cdg[1]); diff --git a/modules/vision/src/pose-estimation/vpPoseLagrange.cpp b/modules/vision/src/pose-estimation/vpPoseLagrange.cpp index 8e073977f3..e0d778dbac 100644 --- a/modules/vision/src/pose-estimation/vpPoseLagrange.cpp +++ b/modules/vision/src/pose-estimation/vpPoseLagrange.cpp @@ -200,19 +200,9 @@ static void lagrange(vpMatrix &a, vpMatrix &b, vpColVector &x1, vpColVector &x2) } #endif - // --comment: vpColVector sv - // --comment: vpMatrix v e.svd(x1, ata); // destructif sur e // calcul du vecteur propre de E correspondant a la valeur propre min. - /* calcul de SVmax */ imin = 0; - // --comment: FC : Pourquoi calculer SVmax ?????? - // --comment: double svm = 0.0; - // --comment: for (i=0;i svm) { svm = x1[i]; imin = i; } - // --comment: } - // --comment: svm *= EPS; /* pour le rang */ unsigned int v_x1_rows = x1.getRows(); for (i = 0; i < v_x1_rows; ++i) { @@ -250,8 +240,6 @@ static void lagrange(vpMatrix &a, vpMatrix &b, vpColVector &x1, vpColVector &x2) #endif } -// --comment: undefine EPS - void vpPose::poseLagrangePlan(vpHomogeneousMatrix &cMo, bool *p_isPlan, double *p_a, double *p_b, double *p_c, double *p_d) { #if (DEBUG_LEVEL1) @@ -317,10 +305,7 @@ void vpPose::poseLagrangePlan(vpHomogeneousMatrix &cMo, bool *p_isPlan, double * r1[1] = n2; r1[2] = (-b * c) / n2; } - // --comment: double norm eq r1[0] mult r1[0] plus r1[1] mult r1[1] plus r1[2] mult r1[2] - // --comment: double crossprod eq r1[0] mult r3[0] plus r1[1] mult r3[1] plus r1[2] mult r3[2] - // --comment: print "r1 norm = 1 ? %lf, r1^T r3 = 0 ? %lf\n" norm crossprod - // --comment: r2 unit vector orthogonal to r3 and r1 + r2 = vpColVector::crossProd(r3, r1); vpHomogeneousMatrix fMo; @@ -418,6 +403,7 @@ void vpPose::poseLagrangePlan(vpHomogeneousMatrix &cMo, bool *p_isPlan, double * s = (X2[0] * X2[0]) + (X2[1] * X2[1]) + (X2[2] * X2[2]); // To avoid a Coverity copy/past error if (s < 1e-10) { + /* // std::cout << "Points that produce an error: " << std::endl; // for (std::list::const_iterator it = listP.begin(); it // != listP.end(); ++it) @@ -427,6 +413,7 @@ void vpPose::poseLagrangePlan(vpHomogeneousMatrix &cMo, bool *p_isPlan, double * // << (*it).get_oX() << " " << (*it).get_oY() << " " << // (*it).get_oZ() << std::endl; // } + */ throw(vpException(vpException::divideByZeroError, "Division by zero in Lagrange pose computation " "(planar plane case)")); } @@ -438,11 +425,6 @@ void vpPose::poseLagrangePlan(vpHomogeneousMatrix &cMo, bool *p_isPlan, double * calculTranslation(A, B, nl, 3, 3, X1, X2); - // --comment: if err diff OK - // --comment: cout "in (vpCalculPose_plan.cc)CalculTranslation returns " - // --comment: PrintError err - // --comment: return err - vpHomogeneousMatrix cMf; /* X1 x X2 */ cMf[0][2] = (X1[1] * X2[2]) - (X1[2] * X2[1]); @@ -461,7 +443,6 @@ void vpPose::poseLagrangePlan(vpHomogeneousMatrix &cMo, bool *p_isPlan, double * #if (DEBUG_LEVEL1) std::cout << "end vpCalculPose::PoseLagrangePlan(...) " << std::endl; #endif - // --comment: return OK } void vpPose::poseLagrangeNonPlan(vpHomogeneousMatrix &cMo) @@ -536,10 +517,6 @@ void vpPose::poseLagrangeNonPlan(vpHomogeneousMatrix &cMo) #endif lagrange(a, b, X1, X2); - // if err not eq OK - // cout "in (CLagrange.cc)Lagrange returns " - // PrintError err - // return err #if (DEBUG_LEVEL2) { @@ -563,6 +540,7 @@ void vpPose::poseLagrangeNonPlan(vpHomogeneousMatrix &cMo) s = (X2[0] * X2[0]) + (X2[1] * X2[1]) + (X2[2] * X2[2]); // To avoid a Coverity copy/past error if (s < 1e-10) { + /* // std::cout << "Points that produce an error: " << std::endl; // for (std::list::const_iterator it = listP.begin(); it // != listP.end(); ++it) @@ -573,6 +551,7 @@ void vpPose::poseLagrangeNonPlan(vpHomogeneousMatrix &cMo) // (*it).get_oZ() << std::endl; // } // vpERROR_TRACE(" division par zero " ) ; + */ throw(vpException(vpException::divideByZeroError, "Division by zero in Lagrange pose computation (non " "planar plane case)")); } diff --git a/modules/vision/src/pose-estimation/vpPoseVirtualVisualServoing.cpp b/modules/vision/src/pose-estimation/vpPoseVirtualVisualServoing.cpp index 65198c9f99..5a47dd1103 100644 --- a/modules/vision/src/pose-estimation/vpPoseVirtualVisualServoing.cpp +++ b/modules/vision/src/pose-estimation/vpPoseVirtualVisualServoing.cpp @@ -74,10 +74,13 @@ void vpPose::poseVirtualVS(vpHomogeneousMatrix &cMo) } vpHomogeneousMatrix cMoPrev = cMo; + /* // --comment: while((int)((residu_1 - r)*1e12) !=0) // --comment: while(std::fabs((residu_1 - r)*1e12) > // --comment: std::numeric_limits < double > :: epsilon()) - while (std::fabs(residu_1 - r) > vvsEpsilon) { + */ + bool iter_gt_vvsitermax = false; + while ((std::fabs(residu_1 - r) > vvsEpsilon) && (iter_gt_vvsitermax == false)) { residu_1 = r; // Compute the interaction matrix and the error @@ -127,7 +130,8 @@ void vpPose::poseVirtualVS(vpHomogeneousMatrix &cMo) cMo = vpExponentialMap::direct(v).inverse() * cMo; if (iter> vvsIterMax) { - break; + iter_gt_vvsitermax = true; + // break } else { ++iter; @@ -184,7 +188,8 @@ void vpPose::poseVirtualVSrobust(vpHomogeneousMatrix &cMo) w = 1; // --comment: while (residu_1 - r) times 1e12 diff 0 - while (std::fabs((residu_1 - r) * 1e12) > std::numeric_limits::epsilon()) { + bool iter_gt_vvsitermax = false; + while ((std::fabs((residu_1 - r) * 1e12) > std::numeric_limits::epsilon()) && (iter_gt_vvsitermax == false)) { residu_1 = r; // Compute the interaction matrix and the error @@ -242,7 +247,8 @@ void vpPose::poseVirtualVSrobust(vpHomogeneousMatrix &cMo) cMo = vpExponentialMap::direct(v).inverse() * cMo; if (iter > vvsIterMax) { - break; + iter_gt_vvsitermax = true; + // break } else { ++iter; diff --git a/tutorial/image/tutorial-canny.cpp b/tutorial/image/tutorial-canny.cpp index 993557ad53..0513b49ef2 100644 --- a/tutorial/image/tutorial-canny.cpp +++ b/tutorial/image/tutorial-canny.cpp @@ -154,8 +154,8 @@ void usage(const std::string &softName, int gaussianKernelSize, float gaussianSt << std::endl; std::cout << "\t-f, --filter " << std::endl << "\t\tPermits to choose the type of filter to apply to compute the gradient." << std::endl - << "\t\tAvailable values: " << vpImageFilter::vpCannyFilteringAndGradientTypeList("<", " | ", ">") << std::endl - << "\t\tDefault: " << vpImageFilter::vpCannyFilteringAndGradientTypeToString(filteringType) << std::endl + << "\t\tAvailable values: " << vpImageFilter::vpGetCannyFiltAndGradTypes("<", " | ", ">") << std::endl + << "\t\tDefault: " << vpImageFilter::vpCannyFiltAndGradTypeToStr(filteringType) << std::endl << std::endl; std::cout << "\t-r, --ratio " << std::endl << "\t\tPermits to set the lower and upper thresholds ratio of the vpCanny class." << std::endl @@ -209,7 +209,7 @@ int main(int argc, const char *argv[]) i++; } else if ((argv_str == "-f" || argv_str == "--filter") && i + 1 < argc) { - opt_filteringType = vpImageFilter::vpCannyFilteringAndGradientTypeFromString(std::string(argv[i + 1])); + opt_filteringType = vpImageFilter::vpCannyFiltAndGradTypeFromStr(std::string(argv[i + 1])); i++; } else if ((argv_str == "-r" || argv_str == "--ratio") && i + 2 < argc) { @@ -234,7 +234,7 @@ int main(int argc, const char *argv[]) } std::string configAsTxt("Canny Configuration:\n"); - configAsTxt += "\tFiltering + gradient operators = " + vpImageFilter::vpCannyFilteringAndGradientTypeToString(opt_filteringType) + "\n"; + configAsTxt += "\tFiltering + gradient operators = " + vpImageFilter::vpCannyFiltAndGradTypeToStr(opt_filteringType) + "\n"; #if (VISP_CXX_STANDARD > VISP_CXX_STANDARD_98) configAsTxt += "\tGaussian filter kernel size = " + std::to_string(opt_gaussianKernelSize) + "\n"; configAsTxt += "\tGaussian filter standard deviation = " + std::to_string(opt_gaussianStdev) + "\n"; diff --git a/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp b/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp index 119173bfb0..46483327e0 100644 --- a/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp +++ b/tutorial/imgproc/hough-transform/tutorial-circle-hough.cpp @@ -251,7 +251,7 @@ int main(int argc, char **argv) i += 2; } else if (argName == "--filtering-type" && i + 1 < argc) { - opt_filteringAndGradientType = vpImageFilter::vpCannyFilteringAndGradientTypeFromString(std::string(argv[i+1])); + opt_filteringAndGradientType = vpImageFilter::vpCannyFiltAndGradTypeFromStr(std::string(argv[i+1])); i++; } else if (argName == "--canny-backend" && i + 1 < argc) { @@ -306,7 +306,7 @@ int main(int argc, char **argv) << "\t [--circle-perfectness ] (default: " << def_circlePerfectness << ")" << std::endl << "\t [--merging-thresh ] (default: centers distance threshold = " << def_centerDistanceThresh << ", radius difference threshold = " << def_radiusDifferenceThresh << ")" << std::endl << "\t [--filtering-type ]" - << " (default: " << vpImageFilter::vpCannyFilteringAndGradientTypeToString(def_filteringAndGradientType) << ")" << std::endl + << " (default: " << vpImageFilter::vpCannyFiltAndGradTypeToStr(def_filteringAndGradientType) << ")" << std::endl << "\t [--canny-backend ]" << " (default: " << vpImageFilter::vpCannyBackendTypeToString(def_cannyBackendType) << ")" << std::endl << "\t [--lower-canny-ratio ]" @@ -417,7 +417,7 @@ int main(int argc, char **argv) << std::endl << "\t--filtering-type" << std::endl << "\t\tPermit to choose the gradient filters." << std::endl - << "\t\tDefault: " << vpImageFilter::vpCannyFilteringAndGradientTypeToString(def_filteringAndGradientType) << ", available: " << vpImageFilter::vpCannyFilteringAndGradientTypeList() << std::endl + << "\t\tDefault: " << vpImageFilter::vpCannyFiltAndGradTypeToStr(def_filteringAndGradientType) << ", available: " << vpImageFilter::vpGetCannyFiltAndGradTypes() << std::endl << std::endl << "\t--canny-backend" << std::endl << "\t\tPermit to choose the backend used to compute the edge map." << std::endl