From 2c238c6bb32c4147ce8c24d1f99e5d4e6826e334 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Mon, 11 Mar 2024 19:44:41 +0100 Subject: [PATCH] Fix various warnings detected with msvc17 --- modules/core/include/visp3/core/vpArray2D.h | 31 ++++++++++++++----- modules/core/include/visp3/core/vpImage.h | 4 ++- .../core/include/visp3/core/vpImageFilter.h | 8 ++--- .../core/include/visp3/core/vpImageTools.h | 5 +-- modules/core/include/visp3/core/vpMunkres.h | 4 +-- modules/core/src/image/vpImageCircle.cpp | 18 +++++------ modules/core/src/image/vpImageFilter.cpp | 2 +- modules/imgproc/src/vpImgproc.cpp | 18 +++++------ .../imgproc/test/with-dataset/testImgproc.cpp | 4 +-- .../io/src/image/private/vpImageIoOpenCV.cpp | 4 +-- modules/io/src/image/private/vpImageIoStb.cpp | 4 +-- .../real-robot/pololu-maestro/vpPololu.cpp | 4 +-- modules/tracker/mbt/src/edge/vpMbtMeLine.cpp | 6 ++-- .../me/src/moving-edges/vpMeEllipse.cpp | 26 +++++++++++----- .../tracker/me/src/moving-edges/vpMeLine.cpp | 26 ++++++++++------ .../vpHomographyRansac.cpp | 2 +- 16 files changed, 102 insertions(+), 64 deletions(-) diff --git a/modules/core/include/visp3/core/vpArray2D.h b/modules/core/include/visp3/core/vpArray2D.h index 5847aca8db..8372741f6a 100644 --- a/modules/core/include/visp3/core/vpArray2D.h +++ b/modules/core/include/visp3/core/vpArray2D.h @@ -320,7 +320,12 @@ template class vpArray2D // Reallocation of this->data array this->dsize = nrows * ncols; - this->data = (Type *)realloc(this->data, this->dsize * sizeof(Type)); + if (this->data) { + Type *tmp = (Type*)realloc(this->data, this->dsize * sizeof(Type)); + if (tmp) { + this->data = tmp; + } + } if ((nullptr == this->data) && (0 != this->dsize)) { if (copyTmp != nullptr) { delete[] copyTmp; @@ -328,7 +333,12 @@ template class vpArray2D throw(vpException(vpException::memoryAllocationError, "Memory allocation error when allocating 2D array data")); } - this->rowPtrs = (Type **)realloc(this->rowPtrs, nrows * sizeof(Type *)); + if (this->rowPtrs) { + Type **tmp = (Type**)realloc(this->rowPtrs, nrows * sizeof(Type*)); + if (tmp) { + this->rowPtrs = tmp; + } + } if ((nullptr == this->rowPtrs) && (0 != this->dsize)) { if (copyTmp != nullptr) { delete[] copyTmp; @@ -389,11 +399,18 @@ template class vpArray2D rowNum = nrows; colNum = ncols; - rowPtrs = reinterpret_cast(realloc(rowPtrs, nrows * sizeof(Type *))); - // Update rowPtrs - Type **t_ = rowPtrs; - for (unsigned int i = 0; i < dsize; i += ncols) { - *t_++ = data + i; + if (rowPtrs) { + Type **tmp = reinterpret_cast(realloc(rowPtrs, nrows * sizeof(Type*))); + if (tmp) { + this->rowPtrs = tmp; + } + } + if (rowPtrs) { + // Update rowPtrs + Type** t_ = rowPtrs; + for (unsigned int i = 0; i < dsize; i += ncols) { + *t_++ = data + i; + } } } diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index b3f82d0794..3687de81e9 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -844,7 +844,9 @@ vpImage::vpImage(const vpImage &I) : bitmap(nullptr), display(nullptr), npixels(0), width(0), height(0), row(nullptr), hasOwnership(true) { resize(I.getHeight(), I.getWidth()); - memcpy(static_cast(bitmap), static_cast(I.bitmap), I.npixels * sizeof(Type)); + if (bitmap) { + memcpy(static_cast(bitmap), static_cast(I.bitmap), I.npixels * sizeof(Type)); + } } #if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher diff --git a/modules/core/include/visp3/core/vpImageFilter.h b/modules/core/include/visp3/core/vpImageFilter.h index ee989955fa..ca778c813f 100644 --- a/modules/core/include/visp3/core/vpImageFilter.h +++ b/modules/core/include/visp3/core/vpImageFilter.h @@ -88,7 +88,7 @@ class VISP_EXPORT vpImageFilter } else { // Need to reset the image because some points will not be computed - I.resize(height, width, static_cast(0.)); + I.resize(height, width, static_cast(0)); } } @@ -227,7 +227,7 @@ class VISP_EXPORT vpImageFilter cv::Mat cv_I, cv_dIx, cv_dIy; vpImageConvert::convert(I, cv_I); computePartialDerivatives(cv_I, cv_dIx, cv_dIy, computeDx, computeDy, normalize, gaussianKernelSize, - gaussianStdev, apertureGradient, filteringType); + static_cast(gaussianStdev), apertureGradient, filteringType); if (computeDx) { vpImageConvert::convert(cv_dIx, dIx); } @@ -796,9 +796,9 @@ class VISP_EXPORT vpImageFilter FilterType result = static_cast(0.); for (unsigned int i = 1; i <= stop; ++i) { - result += filter[i] * static_cast(I[r][c + i] + I[r][c - i]); + result += filter[i] * static_cast(I[r][c + i] + I[r][c - i]); } - return result + filter[0] * static_cast(I[r][c]); + return result + filter[0] * static_cast(I[r][c]); } #ifndef DOXYGEN_SHOULD_SKIP_THIS diff --git a/modules/core/include/visp3/core/vpImageTools.h b/modules/core/include/visp3/core/vpImageTools.h index 6c8fa38269..58a910d885 100644 --- a/modules/core/include/visp3/core/vpImageTools.h +++ b/modules/core/include/visp3/core/vpImageTools.h @@ -57,6 +57,7 @@ #include #include #include +#include #if defined(_OPENMP) #include @@ -1113,12 +1114,12 @@ void vpImageTools::resize(const vpImage &I, vpImage &Ires, const vpI #endif for (int i = 0; i < static_cast(Ires.getHeight()); i++) { const float v = (i + half) * scaleY - half; - const int v0 = static_cast(v); + const float v0 = std::floor(v); const float yFrac = v - v0; for (unsigned int j = 0; j < Ires.getWidth(); j++) { const float u = (j + half) * scaleX - half; - const int u0 = static_cast(u); + const float u0 = std::floor(u); const float xFrac = u - u0; if (method == INTERPOLATION_NEAREST) { diff --git a/modules/core/include/visp3/core/vpMunkres.h b/modules/core/include/visp3/core/vpMunkres.h index 802994da05..6d27fd48d2 100644 --- a/modules/core/include/visp3/core/vpMunkres.h +++ b/modules/core/include/visp3/core/vpMunkres.h @@ -314,8 +314,8 @@ inline vpMunkres::STEP_T vpMunkres::stepSix(std::vector > &cos template inline std::vector > vpMunkres::run(std::vector > costs) { - const auto original_row_size = costs.size(); - const auto original_col_size = costs.front().size(); + const auto original_row_size = static_cast(costs.size()); + const auto original_col_size = static_cast(costs.front().size()); const auto sq_size = std::max(original_row_size, original_col_size); auto mask = std::vector >( diff --git a/modules/core/src/image/vpImageCircle.cpp b/modules/core/src/image/vpImageCircle.cpp index 2bf69365e5..ffeb35c263 100644 --- a/modules/core/src/image/vpImageCircle.cpp +++ b/modules/core/src/image/vpImageCircle.cpp @@ -1043,7 +1043,7 @@ void incrementIfIsInMask(const vpImage &mask, const int &width, const int unsigned int vpImageCircle::computePixelsInMask(const vpImage &mask) const { - const int xm = m_center.get_u(), ym = m_center.get_v(); + const float xm = static_cast(m_center.get_u()), ym = static_cast(m_center.get_v()); const float r_float = static_cast(m_radius); const int width = mask.getWidth(); const int height = mask.getHeight(); @@ -1073,14 +1073,14 @@ unsigned int vpImageCircle::computePixelsInMask(const vpImage &mask) const float sin_theta = std::sin(theta); float rcos_pos = r_float * cos_theta; float rsin_pos = r_float * sin_theta; - x1 = xm + rcos_pos; // theta - y1 = ym + rsin_pos; // theta - x2 = xm - rsin_pos; // theta + pi - y2 = ym + rcos_pos; // theta + pi - x3 = xm - rcos_pos; // theta + pi/2 - y3 = ym - rsin_pos; // theta + pi/2 - x4 = xm + rsin_pos; // theta + pi - y4 = ym - rcos_pos; // theta + pi + x1 = static_cast(xm + rcos_pos); // theta + y1 = static_cast(ym + rsin_pos); // theta + x2 = static_cast(xm - rsin_pos); // theta + pi + y2 = static_cast(ym + rcos_pos); // theta + pi + x3 = static_cast(xm - rcos_pos); // theta + pi/2 + y3 = static_cast(ym - rsin_pos); // theta + pi/2 + x4 = static_cast(xm + rsin_pos); // theta + pi + y4 = static_cast(ym - rcos_pos); // theta + pi incrementIfIsInMask(mask, width, height, x1, y1, count); incrementIfIsInMask(mask, width, height, x2, y2, count); incrementIfIsInMask(mask, width, height, x3, y3, count); diff --git a/modules/core/src/image/vpImageFilter.cpp b/modules/core/src/image/vpImageFilter.cpp index fffa9016d0..a19508fa56 100644 --- a/modules/core/src/image/vpImageFilter.cpp +++ b/modules/core/src/image/vpImageFilter.cpp @@ -1119,7 +1119,7 @@ void vpImageFilter::canny(const vpImage &Isrc, vpImage &I, const vpImage *p_ I.getMinMaxValue(inputMin, inputMax); unsigned char inputRange = inputMax - inputMin; - float gamma_computed = (std::log(128.f) - std::log(256.f)) / (std::log(mean) - std::log(inputRange)); + float gamma_computed = static_cast((std::log(128.f) - std::log(256.f)) / (std::log(mean) - std::log(inputRange))); float inverse_gamma = 1.f / gamma_computed; // Construct the look-up table @@ -397,19 +397,19 @@ void gammaCorrectionClassificationBasedMethod(vpImage &I, const v float gamma = 0.f; if (isAlreadyHighContrast) { // Case medium to high contrast image - gamma = std::exp((1.f - (meanNormalized + stdevNormalized))/2.f); + gamma = static_cast(std::exp((1.f - (meanNormalized + stdevNormalized))/2.f)); } else { // Case low contrast image #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) - gamma = -std::log2(stdevNormalized); + gamma = -static_cast(std::log2(stdevNormalized)); #else - gamma = -std::log(stdevNormalized) / std::log(2); + gamma = -static_cast(std::log(stdevNormalized) / std::log(2)); #endif } if (meanNormalized < 0.5) { // Case dark image - float meanPowerGamma = std::pow(meanNormalized, gamma); + float meanPowerGamma = static_cast(std::pow(meanNormalized, gamma)); for (unsigned int i = 0; i <= 255; i++) { float iNormalized = static_cast(i)/255.f; float iPowerGamma = std::pow(iNormalized, gamma); @@ -500,7 +500,7 @@ void gammaCorrectionSpatialBased(vpImage &I, const vpImage vpImageTools::resize(I_8_blur, L_8, width, height, vpImageTools::INTERPOLATION_CUBIC); const float alpha = 0.5f; unsigned int size = height * width; - float stdev = I.getStdev(p_mask); + float stdev = static_cast(I.getStdev(p_mask)); float p; if (stdev <= 40) { p = 2.f; @@ -546,7 +546,7 @@ void gammaCorrectionSpatialBased(vpImage &I, const vpImage *p_mask vpImage I_gray(height, width); for (unsigned int i = 0; i < size; ++i) { vpRGBa rgb = I.bitmap[i]; - I_gray.bitmap[i] = 0.299 * rgb.R + 0.587 * rgb.G + 0.114 *rgb.B; + I_gray.bitmap[i] = static_cast(0.299 * rgb.R + 0.587 * rgb.G + 0.114 * rgb.B); } vpImage I_2, I_4, I_8; I_gray.subsample(2, 2, I_2); @@ -565,7 +565,7 @@ void gammaCorrectionSpatialBased(vpImage &I, const vpImage *p_mask vpImageTools::resize(I_8_blur, L_8, width, height, vpImageTools::INTERPOLATION_CUBIC); const float alpha = 0.5f; - float stdev = I.getStdev(p_mask); + float stdev = static_cast(I.getStdev(p_mask)); float p; if (stdev <= 40) { p = 2.f; @@ -601,7 +601,7 @@ void gammaCorrection(vpImage &I, const float &gamma, const vpGamm { float inverse_gamma = 1.0; if ((gamma > 0) && (method == GAMMA_MANUAL)) { - inverse_gamma = 1.0 / gamma; + inverse_gamma = 1.0f / gamma; // Construct the look-up table unsigned char lut[256]; for (unsigned int i = 0; i < 256; i++) { diff --git a/modules/imgproc/test/with-dataset/testImgproc.cpp b/modules/imgproc/test/with-dataset/testImgproc.cpp index ba009c23fe..3f2fb03636 100644 --- a/modules/imgproc/test/with-dataset/testImgproc.cpp +++ b/modules/imgproc/test/with-dataset/testImgproc.cpp @@ -273,7 +273,7 @@ int main(int argc, const char **argv) // Gamma correction vpImage I_color_gamma_correction; - double gamma = 2.2; + float gamma = 2.2f; t = vpTime::measureTimeMs(); vp::gammaCorrection(I_color, I_color_gamma_correction, gamma); t = vpTime::measureTimeMs() - t; @@ -376,7 +376,7 @@ int main(int argc, const char **argv) // Gamma correction vpImage I_gamma_correction; - gamma = 1.8; + gamma = 1.8f; t = vpTime::measureTimeMs(); vp::gammaCorrection(I, I_gamma_correction, gamma); t = vpTime::measureTimeMs() - t; diff --git a/modules/io/src/image/private/vpImageIoOpenCV.cpp b/modules/io/src/image/private/vpImageIoOpenCV.cpp index 80a5466150..dceed26214 100644 --- a/modules/io/src/image/private/vpImageIoOpenCV.cpp +++ b/modules/io/src/image/private/vpImageIoOpenCV.cpp @@ -175,7 +175,7 @@ void readOpenCV(vpImage &I, const std::string &filename) */ void readPNGfromMemOpenCV(const std::vector &buffer, vpImage &I) { - cv::Mat1b buf(buffer.size(), 1, const_cast(buffer.data())); + cv::Mat1b buf(static_cast(buffer.size()), 1, const_cast(buffer.data())); cv::Mat1b img = cv::imdecode(buf, cv::IMREAD_GRAYSCALE); I.resize(img.rows, img.cols); std::copy(img.begin(), img.end(), I.bitmap); @@ -189,7 +189,7 @@ void readPNGfromMemOpenCV(const std::vector &buffer, vpImage &buffer, vpImage &I_color) { - cv::Mat1b buf(buffer.size(), 1, const_cast(buffer.data())); + cv::Mat1b buf(static_cast(buffer.size()), 1, const_cast(buffer.data())); cv::Mat3b img = cv::imdecode(buf, cv::IMREAD_COLOR); vpImageConvert::convert(img, I_color); } diff --git a/modules/io/src/image/private/vpImageIoStb.cpp b/modules/io/src/image/private/vpImageIoStb.cpp index 33dc4afa26..55c6699977 100644 --- a/modules/io/src/image/private/vpImageIoStb.cpp +++ b/modules/io/src/image/private/vpImageIoStb.cpp @@ -149,7 +149,7 @@ void readPNGfromMemStb(const std::vector &buffer, vpImage(buffer.size()), &x, &y, &comp, req_channels); assert(comp == req_channels); I.init(buffer_read, y, x, true); @@ -165,7 +165,7 @@ void readPNGfromMemStb(const std::vector &buffer, vpImage &buffer, vpImage &I_color) { int x = 0, y = 0, comp = 0; - unsigned char *buffer_read = stbi_load_from_memory(buffer.data(), buffer.size(), &x, &y, &comp, 0); + unsigned char *buffer_read = stbi_load_from_memory(buffer.data(), static_cast(buffer.size()), &x, &y, &comp, 0); if (comp == 4) { const bool copyData = true; diff --git a/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp b/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp index 43cc96719d..3f631be8fe 100644 --- a/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp +++ b/modules/robot/src/real-robot/pololu-maestro/vpPololu.cpp @@ -122,7 +122,7 @@ unsigned short vpPololu::radToPwm(float angle) const float a = m_range_pwm / m_range_angle; float b = m_min_pwm - m_min_angle * a; - return (a * angle + b); + return static_cast(a * angle + b); } bool vpPololu::connected() const @@ -194,7 +194,7 @@ void vpPololu::setAngularPosition(float pos_rad, float vel_rad_s) { if ((m_min_angle <= pos_rad) && (pos_rad <= m_max_angle)) { unsigned short pos_pwm = radToPwm(pos_rad); - unsigned short pos_speed = std::fabs(radSToSpeed(vel_rad_s)); + unsigned short pos_speed = static_cast(std::fabs(radSToSpeed(vel_rad_s))); // Handle the case where pos_speed = 0 which corresponds to the pwm max speed if (pos_speed == 0) { pos_speed = 1; diff --git a/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp b/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp index 03cc98fa22..cada111ec9 100644 --- a/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp +++ b/modules/tracker/mbt/src/edge/vpMbtMeLine.cpp @@ -173,9 +173,11 @@ void vpMbtMeLine::sample(const vpImage &I, bool doNoTrack) vpImagePoint iP; iP.set_i(is); iP.set_j(js); + unsigned int is_uint = static_cast(is); + unsigned int js_uint = static_cast(js); // If point is in the image, add to the sample list - if ((!outOfImage(iP, (int)(m_me->getRange() + m_me->getMaskSize() + 1), nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) - && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + if ((!outOfImage(iP, (int)(m_me->getRange() + m_me->getMaskSize() + 1), nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint) + && inMeMaskCandidates(m_maskCandidates, is_uint, js_uint)) { vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), m_delta, 0, m_sign); pix.setDisplay(m_selectDisplay); diff --git a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp index 664f440e9a..8f400cc72d 100644 --- a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp @@ -65,7 +65,7 @@ vpMeEllipse::vpMeEllipse(const vpMeEllipse &me_ellipse) m_alphamin(me_ellipse.m_alphamin), m_alphamax(me_ellipse.m_alphamax), m_uc(me_ellipse.m_uc), m_vc(me_ellipse.m_vc), m_n20(me_ellipse.m_n20), m_n11(me_ellipse.m_n11), m_n02(me_ellipse.m_n02), m_expectedDensity(me_ellipse.m_expectedDensity), m_numberOfGoodPoints(me_ellipse.m_numberOfGoodPoints), - m_trackCircle(me_ellipse.m_trackCircle), m_trackArc(me_ellipse.m_trackArc) + m_trackCircle(me_ellipse.m_trackCircle), m_trackArc(me_ellipse.m_trackArc), m_arcEpsilon(me_ellipse.m_arcEpsilon) { } vpMeEllipse::~vpMeEllipse() @@ -300,8 +300,10 @@ void vpMeEllipse::sample(const vpImage &I, bool doNotTrack) computePointOnEllipse(ang, iP); // If point is in the image, add to the sample list // Check done in (i,j) frame) - if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) - && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(iP.get_i()); + unsigned int js_uint = static_cast(iP.get_j()); + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint) + && inMeMaskCandidates(m_maskCandidates, is_uint, js_uint)) { const unsigned int crossSize = 5; vpDisplay::displayCross(I, iP, crossSize, vpColor::red); @@ -361,7 +363,9 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) while (ang < (nextang - incr)) { vpImagePoint iP; computePointOnEllipse(ang, iP); - if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(iP.get_i()); + unsigned int js_uint = static_cast(iP.get_j()); + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint)) { double theta = computeTheta(iP); vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), theta); @@ -420,7 +424,9 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) ang = (nextang + ang) / 2.0; // point added at mid angle vpImagePoint iP; computePointOnEllipse(ang, iP); - if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(iP.get_i()); + unsigned int js_uint = static_cast(iP.get_j()); + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint)) { double theta = computeTheta(iP); vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), theta); @@ -479,7 +485,9 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) for (unsigned int i = 0; i < nbpts; ++i) { vpImagePoint iP; computePointOnEllipse(ang, iP); - if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(iP.get_i()); + unsigned int js_uint = static_cast(iP.get_j()); + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint)) { double theta = computeTheta(iP); vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), theta); @@ -529,7 +537,9 @@ unsigned int vpMeEllipse::plugHoles(const vpImage &I) for (unsigned int i = 0; i < nbpts; ++i) { vpImagePoint iP; computePointOnEllipse(ang, iP); - if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(iP.get_i()); + unsigned int js_uint = static_cast(iP.get_j()); + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint)) { double theta = computeTheta(iP); vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), theta); @@ -1241,7 +1251,7 @@ void vpMeEllipse::initTracking(const vpImage &I, const vpColVecto computeAbeFromNij(); computeKiFromNij(); - if (m_trackArc) { + if (m_trackArc && pt1 && pt2) { m_alpha1 = computeAngleOnEllipse(*pt1); m_alpha2 = computeAngleOnEllipse(*pt2); if ((m_alpha2 <= m_alpha1) || (std::fabs(m_alpha2 - m_alpha1) < m_arcEpsilon)) { diff --git a/modules/tracker/me/src/moving-edges/vpMeLine.cpp b/modules/tracker/me/src/moving-edges/vpMeLine.cpp index 41501bd559..39e01e785f 100644 --- a/modules/tracker/me/src/moving-edges/vpMeLine.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeLine.cpp @@ -161,9 +161,11 @@ void vpMeLine::sample(const vpImage &I, bool doNotTrack) vpImagePoint iP; iP.set_i(is); iP.set_j(js); + unsigned int is_uint = static_cast(is); + unsigned int js_uint = static_cast(js); // If point is in the image, add to the sample list - if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) - && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + if ((!outOfImage(iP, 0, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint) + && inMeMaskCandidates(m_maskCandidates, is_uint, js_uint)) { vpMeSite pix; pix.init(iP.get_i(), iP.get_j(), m_delta, 0, m_sign); pix.setDisplay(m_selectDisplay); @@ -523,16 +525,18 @@ void vpMeLine::seekExtremities(const vpImage &I) for (int i = 0; i < 3; i++) { P.m_ifloat = P.m_ifloat + di * sample_step; - P.m_i = (int)P.m_ifloat; + P.m_i = static_cast(P.m_ifloat); P.m_jfloat = P.m_jfloat + dj * sample_step; - P.m_j = (int)P.m_jfloat; + P.m_j = static_cast(P.m_jfloat); vpImagePoint iP; iP.set_i(P.m_ifloat); iP.set_j(P.m_jfloat); - if ((!outOfImage(iP, 5, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) - && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(P.m_ifloat); + unsigned int js_uint = static_cast(P.m_jfloat); + if ((!outOfImage(iP, 5, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint) + && inMeMaskCandidates(m_maskCandidates, is_uint, js_uint)) { P.track(I, m_me, false); if (P.getState() == vpMeSite::NO_SUPPRESSION) { @@ -553,16 +557,18 @@ void vpMeLine::seekExtremities(const vpImage &I) P.setDisplay(m_selectDisplay); for (int i = 0; i < 3; i++) { P.m_ifloat = P.m_ifloat - di * sample_step; - P.m_i = (int)P.m_ifloat; + P.m_i = static_cast(P.m_ifloat); P.m_jfloat = P.m_jfloat - dj * sample_step; - P.m_j = (int)P.m_jfloat; + P.m_j = static_cast(P.m_jfloat); vpImagePoint iP; iP.set_i(P.m_ifloat); iP.set_j(P.m_jfloat); - if ((!outOfImage(iP, 5, nbrows, nbcols)) && inRoiMask(m_mask, iP.get_i(), iP.get_j()) - && inMeMaskCandidates(m_maskCandidates, iP.get_i(), iP.get_j())) { + unsigned int is_uint = static_cast(P.m_ifloat); + unsigned int js_uint = static_cast(P.m_jfloat); + if ((!outOfImage(iP, 5, nbrows, nbcols)) && inRoiMask(m_mask, is_uint, js_uint) + && inMeMaskCandidates(m_maskCandidates, is_uint, js_uint)) { P.track(I, m_me, false); if (P.getState() == vpMeSite::NO_SUPPRESSION) { diff --git a/modules/vision/src/homography-estimation/vpHomographyRansac.cpp b/modules/vision/src/homography-estimation/vpHomographyRansac.cpp index 80db43742d..816b71785d 100644 --- a/modules/vision/src/homography-estimation/vpHomographyRansac.cpp +++ b/modules/vision/src/homography-estimation/vpHomographyRansac.cpp @@ -432,7 +432,7 @@ bool vpHomography::ransac(const std::vector &xb, const std::vector= nbInliersConsensus) { - const unsigned int nbConsensus = best_consensus.size(); + const unsigned int nbConsensus = static_cast(best_consensus.size()); std::vector xa_best(nbConsensus); std::vector ya_best(nbConsensus); std::vector xb_best(nbConsensus);