From 4c27c7cd020f0e663c77b1414f797d760f56df11 Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Mon, 30 Sep 2024 23:11:46 +0200 Subject: [PATCH] Fix warnings detected on windows with msvc17 --- 3rdparty/apriltag/CMakeLists.txt | 1 + .../device/framegrabber/readRealSenseData.cpp | 12 +++--- .../device/framegrabber/saveRealSenseData.cpp | 14 +++---- modules/core/include/visp3/core/vpIoTools.h | 2 +- .../include/visp3/core/vpParticleFilter.h | 2 +- modules/core/src/tools/network/vpClient.cpp | 2 +- modules/core/src/tools/network/vpNetwork.cpp | 2 +- modules/core/src/tools/network/vpServer.cpp | 2 +- modules/core/test/math/testParticleFilter.cpp | 38 +++++++++---------- .../tutorial-pf-curve-fitting-all.cpp | 38 +++++++++---------- .../tutorial-pf-curve-fitting-lms.cpp | 10 ++--- .../tutorial-pf-curve-fitting-pf.cpp | 32 ++++++++-------- .../vpTutoMeanSquareFitting.cpp | 8 ++-- .../vpTutoMeanSquareFitting.h | 8 ++-- .../vpTutoParabolaModel.h | 18 ++++----- .../vpTutoSegmentation.cpp | 8 ++-- tutorial/particle-filter/tutorial-pf.cpp | 2 +- .../tutorial-mb-generic-tracker-full.cpp | 18 ++++----- 18 files changed, 109 insertions(+), 108 deletions(-) diff --git a/3rdparty/apriltag/CMakeLists.txt b/3rdparty/apriltag/CMakeLists.txt index f685f0e6b0..b3308b4e83 100644 --- a/3rdparty/apriltag/CMakeLists.txt +++ b/3rdparty/apriltag/CMakeLists.txt @@ -77,6 +77,7 @@ if(MSVC) vp_set_source_file_compile_flag(tag25h9.c /wd4996) vp_set_source_file_compile_flag(tag36h10.c /wd4996) vp_set_source_file_compile_flag(tag36h11.c /wd4996) + vp_set_source_file_compile_flag(tagCircle21h7.c /wd4996) # disable optimization foreach(f ${tag_srcs}) vp_set_source_file_compile_flag(${f} /O0) diff --git a/example/device/framegrabber/readRealSenseData.cpp b/example/device/framegrabber/readRealSenseData.cpp index f4bde88236..24ba124a22 100644 --- a/example/device/framegrabber/readRealSenseData.cpp +++ b/example/device/framegrabber/readRealSenseData.cpp @@ -68,7 +68,7 @@ #endif #endif -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) #define GETOPTARGS "ci:e:jbzodh" #else #define GETOPTARGS "ci:e:jbodh" @@ -94,7 +94,7 @@ void usage(const char *name, const char *badparam) << " [-c]" << " [-j]" << " [-b]" -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) << " [-z]" #endif << " [-o]" @@ -117,7 +117,7 @@ void usage(const char *name, const char *badparam) << " -b" << std::endl << " Depth and Pointcloud streams are saved in binary format." << std::endl << std::endl -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) << " -z" << std::endl << " Pointcloud stream is saved in NPZ format." << std::endl << std::endl @@ -161,7 +161,7 @@ bool getOptions(int argc, const char *argv[], std::string &input_directory, std: case 'b': force_binary_format = true; break; -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) case 'z': read_npz = true; break; @@ -252,7 +252,7 @@ bool readData(int cpt, const std::string &input_directory, const std::string &pa } } } -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) else { visp::cnpy::npz_t npz_data = visp::cnpy::npz_load(filename_depth); @@ -312,7 +312,7 @@ bool readData(int cpt, const std::string &input_directory, const std::string &pa } } } -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) else if (read_npz) { visp::cnpy::npz_t npz_data = visp::cnpy::npz_load(filename_pointcloud); diff --git a/example/device/framegrabber/saveRealSenseData.cpp b/example/device/framegrabber/saveRealSenseData.cpp index fc14bb66bb..fc18d6e896 100644 --- a/example/device/framegrabber/saveRealSenseData.cpp +++ b/example/device/framegrabber/saveRealSenseData.cpp @@ -74,7 +74,7 @@ #define USE_REALSENSE2 #endif -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) #define GETOPTARGS "se:o:acdpzijCf:bvh" #else #define GETOPTARGS "se:o:acdpijCf:bvh" @@ -97,7 +97,7 @@ void usage(const char *name, const char *badparam, int fps) << " [-d]" << " [-p]" << " [-b]" -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) << " [-z]" #endif << " [-i]" @@ -133,7 +133,7 @@ void usage(const char *name, const char *badparam, int fps) << " -b" << std::endl << " Force depth and pointcloud to be saved in (little-endian) binary format." << std::endl << std::endl -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) << " -z" << std::endl << " Pointcloud is saved in NPZ format." << std::endl << std::endl @@ -220,7 +220,7 @@ bool getOptions(int argc, const char *argv[], bool &save, std::string &pattern, case 'v': depth_hist_visu = true; break; -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) case 'z': save_pcl_npz_format = true; break; @@ -481,7 +481,7 @@ class vpStorageWorker } } } -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) else { ss << m_directory << "/depth_image_" << m_save_pattern << ".npz"; snprintf(buffer, FILENAME_MAX, ss.str().c_str(), m_cpt); @@ -575,7 +575,7 @@ class vpStorageWorker } } else if (m_save_pcl_npz_format) { -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) // Write Npz headers std::vector vec_filename(filename_point_cloud.begin(), filename_point_cloud.end()); // Null-terminated character is handled at reading @@ -708,7 +708,7 @@ int main(int argc, const char *argv[]) std::cout << "save_jpeg: " << save_jpeg << std::endl; std::cout << "stream_fps: " << stream_fps << std::endl; std::cout << "depth_hist_visu: " << depth_hist_visu << std::endl; -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) std::cout << "save_pcl_npz_format: " << save_pcl_npz_format << std::endl; #endif std::cout << "save_force_binary_format: " << save_force_binary_format << std::endl; diff --git a/modules/core/include/visp3/core/vpIoTools.h b/modules/core/include/visp3/core/vpIoTools.h index 511b1333b5..b35a341ab6 100644 --- a/modules/core/include/visp3/core/vpIoTools.h +++ b/modules/core/include/visp3/core/vpIoTools.h @@ -77,7 +77,7 @@ static inline unsigned long vp_mz_crc32(unsigned long crc, const unsigned char * } #endif // DOXYGEN_SHOULD_SKIP_THIS -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) namespace cnpy { // Copyright (C) 2011 Carl Rogers diff --git a/modules/core/include/visp3/core/vpParticleFilter.h b/modules/core/include/visp3/core/vpParticleFilter.h index 169de74011..c244af11ac 100644 --- a/modules/core/include/visp3/core/vpParticleFilter.h +++ b/modules/core/include/visp3/core/vpParticleFilter.h @@ -462,7 +462,7 @@ vpParticleFilter::vpParticleFilter(const unsigned int &N, cons vpUniRand seedGenerator(seedForGenerator); for (unsigned int threadId = 0; threadId < m_nbMaxThreads; ++threadId) { for (unsigned int stateId = 0; stateId < sizeState; ++stateId) { - m_noiseGenerators[threadId].push_back(vpGaussRand(stdev[stateId], 0., seedGenerator.uniform(0., 1e9))); + m_noiseGenerators[threadId].push_back(vpGaussRand(stdev[stateId], 0., static_cast(seedGenerator.uniform(0., 1e9)))); } } } diff --git a/modules/core/src/tools/network/vpClient.cpp b/modules/core/src/tools/network/vpClient.cpp index 12fc072ba3..d08c34a7dc 100644 --- a/modules/core/src/tools/network/vpClient.cpp +++ b/modules/core/src/tools/network/vpClient.cpp @@ -35,7 +35,7 @@ // Specific case for UWP to introduce a workaround // error C4996: 'gethostbyname': Use getaddrinfo() or GetAddrInfoW() instead or define _WINSOCK_DEPRECATED_NO_WARNINGS to disable deprecated API warnings -#if defined(WINRT) +#if defined(WINRT) || defined(_WIN32) #ifndef _WINSOCK_DEPRECATED_NO_WARNINGS #define _WINSOCK_DEPRECATED_NO_WARNINGS #endif diff --git a/modules/core/src/tools/network/vpNetwork.cpp b/modules/core/src/tools/network/vpNetwork.cpp index e03dd344b3..58cee1755f 100644 --- a/modules/core/src/tools/network/vpNetwork.cpp +++ b/modules/core/src/tools/network/vpNetwork.cpp @@ -35,7 +35,7 @@ // Specific case for UWP to introduce a workaround // error C4996: 'gethostbyname': Use getaddrinfo() or GetAddrInfoW() instead or define _WINSOCK_DEPRECATED_NO_WARNINGS to disable deprecated API warnings -#if defined(WINRT) +#if defined(WINRT) || defined(_WIN32) #ifndef _WINSOCK_DEPRECATED_NO_WARNINGS #define _WINSOCK_DEPRECATED_NO_WARNINGS #endif diff --git a/modules/core/src/tools/network/vpServer.cpp b/modules/core/src/tools/network/vpServer.cpp index 4b71f22158..a8714f291b 100644 --- a/modules/core/src/tools/network/vpServer.cpp +++ b/modules/core/src/tools/network/vpServer.cpp @@ -35,7 +35,7 @@ // Specific case for UWP to introduce a workaround // error C4996: 'gethostbyname': Use getaddrinfo() or GetAddrInfoW() instead or define _WINSOCK_DEPRECATED_NO_WARNINGS to disable deprecated API warnings -#if defined(WINRT) +#if defined(WINRT) || defined(_WIN32) #ifndef _WINSOCK_DEPRECATED_NO_WARNINGS #define _WINSOCK_DEPRECATED_NO_WARNINGS #endif diff --git a/modules/core/test/math/testParticleFilter.cpp b/modules/core/test/math/testParticleFilter.cpp index 4e0f949b0d..de012553db 100644 --- a/modules/core/test/math/testParticleFilter.cpp +++ b/modules/core/test/math/testParticleFilter.cpp @@ -73,8 +73,8 @@ class vpParabolaModel public: inline vpParabolaModel(const unsigned int °ree, const unsigned int &height, const unsigned int &width) : m_degree(degree) - , m_height(static_cast(height)) - , m_width(static_cast(width)) + , m_height(height) + , m_width(width) , m_coeffs(degree + 1, 0.) { } @@ -88,8 +88,8 @@ class vpParabolaModel */ inline vpParabolaModel(const vpColVector &coeffs, const unsigned int &height, const unsigned int &width) : m_degree(coeffs.size() - 1) - , m_height(static_cast(height)) - , m_width(static_cast(width)) + , m_height(height) + , m_width(width) , m_coeffs(coeffs) { } @@ -103,8 +103,8 @@ class vpParabolaModel */ inline vpParabolaModel(const vpMatrix &coeffs, const unsigned int &height, const unsigned int &width) : m_degree(coeffs.getRows() - 1) - , m_height(static_cast(height)) - , m_width(static_cast(width)) + , m_height(height) + , m_width(width) , m_coeffs(coeffs.getCol(0)) { } @@ -163,9 +163,9 @@ class vpParabolaModel * \param[out] b The matrix that contains the v-coordinates. * \return Fill */ - static void fillSystem(const unsigned int °ree, const double &height, const double &width, const std::vector< vpImagePoint> &pts, vpMatrix &A, vpMatrix &b) + static void fillSystem(const unsigned int °ree, const unsigned int &height, const unsigned int&width, const std::vector< vpImagePoint> &pts, vpMatrix &A, vpMatrix &b) { - const unsigned int nbPts = pts.size(); + const unsigned int nbPts = static_cast(pts.size()); const unsigned int nbCoeffs = degree + 1; std::vector normalizedPts; for (const auto &pt: pts) { @@ -197,7 +197,7 @@ class vpParabolaModel { unsigned int width = I.getWidth(); for (unsigned int u = 0; u < width; ++u) { - int v = eval(u); + int v = static_cast(eval(u)); vpDisplay::displayPoint(I, v, u, color, 1); vpDisplay::displayText(I, vertPosLegend, horPosLegend, legend, color); } @@ -206,8 +206,8 @@ class vpParabolaModel private: unsigned int m_degree; /*!< The highest degree of the polynomial.*/ - double m_height; /*!< The height of the input image*/ - double m_width; /*!< The width of the input image*/ + unsigned int m_height; /*!< The height of the input image*/ + unsigned int m_width; /*!< The width of the input image*/ vpColVector m_coeffs; /*!< The coefficient of the polynomial, where m_coeffs[0] is the offset and m_coeffs[m_degree] is the coefficient applied to the highest degree.*/ }; @@ -292,7 +292,7 @@ template void displayGeneratedImage(const vpImage &I, const std::vector &pts, const vpColor &color, const std::string &legend, const unsigned int &vertOffset, const unsigned int &horOffset) { - unsigned int nbPts = pts.size(); + unsigned int nbPts = static_cast(pts.size()); for (unsigned int i = 1; i < nbPts; ++i) { vpDisplay::displayPoint(I, pts[i], color, 1); } @@ -309,7 +309,7 @@ void displayGeneratedImage(const vpImage &I, const std::vector * \param[in] width The maximum x-coordinate. * \return vpParabolaModel The fitter model. */ -vpParabolaModel computeInitialGuess(const std::vector &pts, const unsigned int °ree, const double &height, const double &width) +vpParabolaModel computeInitialGuess(const std::vector &pts, const unsigned int °ree, const unsigned int&height, const unsigned int &width) { vpMatrix A; // The matrix that contains the u^2, u and 1s vpMatrix X; // The matrix we want to estimate, that contains the a, b and c coefficients. @@ -370,7 +370,7 @@ class vpAverageFunctor vpColVector averagePolynomials(const std::vector &particles, const std::vector &weights, const vpParticleFilter>::vpStateAddFunction &/**/) { - const unsigned int nbParticles = particles.size(); + const unsigned int nbParticles = static_cast(particles.size()); const double nbParticlesAsDOuble = static_cast(nbParticles); const double sumWeight = std::accumulate(weights.begin(), weights.end(), 0.); const double nbPointsForAverage = 10. * nbParticlesAsDOuble; @@ -442,7 +442,7 @@ class vpLikelihoodFunctor double likelihood(const vpColVector &coeffs, const std::vector &meas) { double likelihood = 0.; - unsigned int nbPoints = meas.size(); + unsigned int nbPoints = static_cast(meas.size()); vpParabolaModel model(coeffs, m_height, m_width); vpColVector residuals(nbPoints); double rmse = evaluate(meas, model); @@ -463,8 +463,8 @@ class vpLikelihoodFunctor TEST_CASE("2nd-degree", "[vpParticleFilter][Polynomial interpolation]") { /// ----- Simulation parameters ----- - const double width = 600.; //!< The width of the simulated image - const double height = 400.; //!< The height of the simulated image + const unsigned int width = 600; //!< The width of the simulated image + const unsigned int height = 400; //!< The height of the simulated image const unsigned int degree = 2; //!< The degree of the polynomial in the simulated image const unsigned int nbInitPoints = 10; //!< Number of points to compute the initial guess of the PF state const uint64_t seedCurve = 4224; //!< The seed to generate the curve @@ -648,8 +648,8 @@ TEST_CASE("2nd-degree", "[vpParticleFilter][Polynomial interpolation]") TEST_CASE("3rd-degree", "[vpParticleFilter][Polynomial interpolation]") { /// ----- Simulation parameters ----- - const double width = 600.; //!< The width of the simulated image - const double height = 400.; //!< The height of the simulated image + const unsigned int width = 600; //!< The width of the simulated image + const unsigned int height = 400; //!< The height of the simulated image const unsigned int degree = 3; //!< The degree of the polynomial in the simulated image const unsigned int nbInitPoints = 10; //!< Number of points to compute the initial guess of the PF state const uint64_t seedCurve = 4224; //!< The seed to generate the curve diff --git a/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-all.cpp b/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-all.cpp index 9528d18de5..7ec4a7cb5d 100644 --- a/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-all.cpp +++ b/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-all.cpp @@ -91,7 +91,7 @@ double evaluate(const vpImagePoint &pt, const vpTutoParabolaModel &model) */ double evaluate(const vpColVector &coeffs, const unsigned int &height, const unsigned int &width, const std::vector &pts) { - unsigned int nbPts = pts.size(); + unsigned int nbPts = static_cast(pts.size()); vpColVector residuals(nbPts); vpColVector weights(nbPts, 1.); vpTutoParabolaModel model(coeffs, height, width); @@ -122,7 +122,7 @@ void display(const vpColVector &coeffs, const vpImage &I, const vpColor &colo unsigned int width = I.getWidth(); vpTutoParabolaModel model(coeffs, I.getHeight(), I.getWidth()); for (unsigned int u = 0; u < width; ++u) { - float v = model.eval(u); + unsigned int v = static_cast(model.eval(u)); vpDisplay::displayPoint(I, v, u, color, 1); vpDisplay::displayText(I, vertPosLegend, horPosLegend, "Particle Filter model", color); } @@ -156,7 +156,7 @@ std::vector automaticInitialization(tutorial::vpTutoCommonData &da // Extracting the skeleton of the mask std::vector edgePoints = tutorial::extractSkeleton(data); - unsigned int nbEdgePoints = edgePoints.size(); + unsigned int nbEdgePoints = static_cast(edgePoints.size()); if (nbEdgePoints < nbPtsToUse) { return edgePoints; @@ -172,12 +172,12 @@ std::vector automaticInitialization(tutorial::vpTutoCommonData &da if (nbEdgePoints > nbPtsToUse + 20) { // Avoid extreme points in case it's noise idStart = 10; - idStop = edgePoints.size() - 10; + idStop = static_cast(edgePoints.size()) - 10; } else { // We need to take all the points because we don't have enough idStart = 0; - idStop = edgePoints.size(); + idStop = static_cast(edgePoints.size()); } // Sample uniformly the points starting from the left of the image to the right @@ -222,7 +222,7 @@ std::vector manualInitialization(const tutorial::vpTutoCommonData vpDisplay::displayText(data.m_I_orig, data.m_ipLegend + data.m_legendOffset + data.m_legendOffset, "If not enough points have been selected, a right click has no effect.", data.m_colorLegend); // Display the already selected points - unsigned int nbInitPoints = initPoints.size(); + unsigned int nbInitPoints = static_cast(initPoints.size()); for (unsigned int i = 0; i < nbInitPoints; ++i) { vpDisplay::displayCross(data.m_I_orig, initPoints[i], sizeCross, colorCross, thicknessCross); } @@ -325,14 +325,14 @@ vpColVector computeInitialGuess(tutorial::vpTutoCommonData &data) // Display info about the initialization vpDisplay::display(data.m_I_orig); vpDisplay::displayText(data.m_I_orig, data.m_ipLegend, "Here are the points selected for the initialization.", data.m_colorLegend); - unsigned int nbInitPoints = initPoints.size(); - for (unsigned int i = 0; i < nbInitPoints; ++i) { + size_t nbInitPoints = initPoints.size(); + for (size_t i = 0; i < nbInitPoints; ++i) { const vpImagePoint &ip = initPoints[i]; vpDisplay::displayCross(data.m_I_orig, ip, sizeCross, colorCross, thicknessCross); } // Update display and wait for click - lmsFitter.display(data.m_I_orig, vpColor::red, data.m_ipLegend.get_v() + 2 * data.m_legendOffset.get_v(), data.m_ipLegend.get_u()); + lmsFitter.display(data.m_I_orig, vpColor::red, static_cast(data.m_ipLegend.get_v() + 2 * data.m_legendOffset.get_v()), static_cast(data.m_ipLegend.get_u())); vpDisplay::displayText(data.m_I_orig, data.m_ipLegend + data.m_legendOffset, "A click to continue.", data.m_colorLegend); vpDisplay::flush(data.m_I_orig); vpDisplay::getClick(data.m_I_orig, waitForClick); @@ -370,7 +370,7 @@ class vpTutoAverageFunctor */ vpColVector averagePolynomials(const std::vector &particles, const std::vector &weights, const vpParticleFilter>::vpStateAddFunction &/**/) { - const unsigned int nbParticles = particles.size(); + const unsigned int nbParticles = static_cast(particles.size()); const double nbParticlesAsDOuble = static_cast(nbParticles); // Compute the sum of the weights to be able to determine the "importance" of a particle with regard to the whole set const double sumWeight = std::accumulate(weights.begin(), weights.end(), 0.); @@ -454,7 +454,7 @@ class vpTutoLikelihoodFunctor double likelihood(const vpColVector &coeffs, const std::vector &meas) { double likelihood = 0.; - unsigned int nbPoints = meas.size(); + unsigned int nbPoints = static_cast(meas.size()); // Generate a model from the coefficients stored in the particle state vpTutoParabolaModel model(coeffs, m_height, m_width); @@ -497,8 +497,8 @@ int main(const int argc, const char *argv[]) return returnCode; } tutorial::vpTutoMeanSquareFitting lmsFitter(data.m_degree, data.m_I_orig.getHeight(), data.m_I_orig.getWidth()); - const unsigned int vertOffset = data.m_legendOffset.get_i(); - const unsigned int horOffset = data.m_ipLegend.get_j(); + const unsigned int vertOffset = static_cast(data.m_legendOffset.get_i()); + const unsigned int horOffset = static_cast(data.m_ipLegend.get_j()); const unsigned int legendLmsVert = data.m_I_orig.getHeight() - 3 * vertOffset; const unsigned int legendLmsHor = horOffset; const unsigned int legendPFVert = data.m_I_orig.getHeight() - 2 * vertOffset, legendPFHor = horOffset; @@ -518,9 +518,9 @@ int main(const int argc, const char *argv[]) stdevsPF.push_back(ampliMax / 3.); } unsigned long seedPF; // Seed for the random generators of the PF - const float period = 33.3; // 33.3ms i.e. 30Hz + const float period = 33.3f; // 33.3ms i.e. 30Hz if (data.m_pfSeed < 0) { - seedPF = vpTime::measureTimeMicros(); + seedPF = static_cast(vpTime::measureTimeMicros()); } else { seedPF = data.m_pfSeed; @@ -550,8 +550,8 @@ int main(const int argc, const char *argv[]) //! [Init_plot] #ifdef VISP_HAVE_DISPLAY unsigned int plotHeight = 350, plotWidth = 350; - int plotXpos = data.m_legendOffset.get_u(); - int plotYpos = data.m_I_orig.getHeight() + 4. * data.m_legendOffset.get_v(); + int plotXpos = static_cast(data.m_legendOffset.get_u()); + int plotYpos = static_cast(data.m_I_orig.getHeight() + 4. * data.m_legendOffset.get_v()); vpPlot plot(1, plotHeight, plotWidth, plotXpos, plotYpos, "Root mean-square error"); plot.initGraph(0, 2); plot.setLegend(0, 0, "LMS estimator"); @@ -588,7 +588,7 @@ int main(const int argc, const char *argv[]) double tLms = vpTime::measureTimeMs(); lmsFitter.fit(noisyEdgePoints); double dtLms = vpTime::measureTimeMs() - tLms; - float lmsRootMeanSquareError = lmsFitter.evaluate(edgePoints); + double lmsRootMeanSquareError = lmsFitter.evaluate(edgePoints); std::cout << " [Least-Mean Square method] " << std::endl; std::cout << " Coeffs = [" << lmsFitter.getCoeffs().transpose() << " ]" << std::endl; std::cout << " Root Mean Square Error = " << lmsRootMeanSquareError << " pixels" << std::endl; @@ -608,7 +608,7 @@ int main(const int argc, const char *argv[]) //! [Get_filtered_state] //! [Evaluate_performances] - float pfError = tutorial::evaluate(Xest, data.m_I_orig.getHeight(), data.m_I_orig.getWidth(), edgePoints); + double pfError = tutorial::evaluate(Xest, data.m_I_orig.getHeight(), data.m_I_orig.getWidth(), edgePoints); //! [Evaluate_performances] std::cout << " [Particle Filter method] " << std::endl; std::cout << " Coeffs = [" << Xest.transpose() << " ]" << std::endl; diff --git a/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-lms.cpp b/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-lms.cpp index 381256e595..96f637f1a9 100644 --- a/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-lms.cpp +++ b/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-lms.cpp @@ -57,16 +57,16 @@ int main(const int argc, const char *argv[]) return returnCode; } tutorial::vpTutoMeanSquareFitting lmsFitter(data.m_degree, data.m_I_orig.getHeight(), data.m_I_orig.getWidth()); - const unsigned int vertOffset = data.m_legendOffset.get_i(); - const unsigned int horOffset = data.m_ipLegend.get_j(); + const unsigned int vertOffset = static_cast(data.m_legendOffset.get_i()); + const unsigned int horOffset = static_cast(data.m_ipLegend.get_j()); const unsigned int legendLmsVert = data.m_I_orig.getHeight() - 2 * vertOffset; const unsigned int legendLmsHor = horOffset; //! [Init_plot] #ifdef VISP_HAVE_DISPLAY unsigned int plotHeight = 350, plotWidth = 350; - int plotXpos = data.m_legendOffset.get_u(); - int plotYpos = data.m_I_orig.getHeight() + 4. * data.m_legendOffset.get_v(); + int plotXpos = static_cast(data.m_legendOffset.get_u()); + int plotYpos = static_cast(data.m_I_orig.getHeight() + 4. * data.m_legendOffset.get_v()); vpPlot plot(1, plotHeight, plotWidth, plotXpos, plotYpos, "Root mean-square error"); plot.initGraph(0, 1); plot.setLegend(0, 0, "LMS estimator"); @@ -106,7 +106,7 @@ int main(const int argc, const char *argv[]) lmsFitter.fit(noisyEdgePoints); //! [LMS_interpolation] double dtLms = vpTime::measureTimeMs() - tLms; - float lmsRootMeanSquareError = lmsFitter.evaluate(edgePoints); + double lmsRootMeanSquareError = lmsFitter.evaluate(edgePoints); std::cout << " [Least-Mean Square method] " << std::endl; std::cout << " Coeffs = [" << lmsFitter.getCoeffs().transpose() << " ]" << std::endl; std::cout << " Root Mean Square Error = " << lmsRootMeanSquareError << " pixels" << std::endl; diff --git a/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-pf.cpp b/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-pf.cpp index 9f605abf89..4c48f65328 100644 --- a/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-pf.cpp +++ b/tutorial/particle-filter-curve-fitting/tutorial-pf-curve-fitting-pf.cpp @@ -87,7 +87,7 @@ double evaluate(const vpImagePoint &pt, const vpTutoParabolaModel &model) */ double evaluate(const vpColVector &coeffs, const unsigned int &height, const unsigned int &width, const std::vector &pts) { - unsigned int nbPts = pts.size(); + unsigned int nbPts = static_cast(pts.size()); vpColVector residuals(nbPts); vpColVector weights(nbPts, 1.); vpTutoParabolaModel model(coeffs, height, width); @@ -152,7 +152,7 @@ std::vector automaticInitialization(tutorial::vpTutoCommonData &da // Extracting the skeleton of the mask std::vector edgePoints = tutorial::extractSkeleton(data); - unsigned int nbEdgePoints = edgePoints.size(); + unsigned int nbEdgePoints = static_cast(edgePoints.size()); if (nbEdgePoints < nbPtsToUse) { return edgePoints; @@ -168,12 +168,12 @@ std::vector automaticInitialization(tutorial::vpTutoCommonData &da if (nbEdgePoints > nbPtsToUse + 20) { // Avoid extreme points in case it's noise idStart = 10; - idStop = edgePoints.size() - 10; + idStop = static_cast(edgePoints.size()) - 10; } else { // We need to take all the points because we don't have enough idStart = 0; - idStop = edgePoints.size(); + idStop = static_cast(edgePoints.size()); } // Sample uniformly the points starting from the left of the image to the right @@ -218,7 +218,7 @@ std::vector manualInitialization(const tutorial::vpTutoCommonData vpDisplay::displayText(data.m_I_orig, data.m_ipLegend + data.m_legendOffset + data.m_legendOffset, "If not enough points have been selected, a right click has no effect.", data.m_colorLegend); // Display the already selected points - unsigned int nbInitPoints = initPoints.size(); + unsigned int nbInitPoints = static_cast(initPoints.size()); for (unsigned int i = 0; i < nbInitPoints; ++i) { vpDisplay::displayCross(data.m_I_orig, initPoints[i], sizeCross, colorCross, thicknessCross); } @@ -321,14 +321,14 @@ vpColVector computeInitialGuess(tutorial::vpTutoCommonData &data) // Display info about the initialization vpDisplay::display(data.m_I_orig); vpDisplay::displayText(data.m_I_orig, data.m_ipLegend, "Here are the points selected for the initialization.", data.m_colorLegend); - unsigned int nbInitPoints = initPoints.size(); + unsigned int nbInitPoints = static_cast(initPoints.size()); for (unsigned int i = 0; i < nbInitPoints; ++i) { const vpImagePoint &ip = initPoints[i]; vpDisplay::displayCross(data.m_I_orig, ip, sizeCross, colorCross, thicknessCross); } // Update display and wait for click - lmsFitter.display(data.m_I_orig, vpColor::red, data.m_ipLegend.get_v() + 2 * data.m_legendOffset.get_v(), data.m_ipLegend.get_u()); + lmsFitter.display(data.m_I_orig, vpColor::red, static_cast(data.m_ipLegend.get_v() + 2 * data.m_legendOffset.get_v()), static_cast(data.m_ipLegend.get_u())); vpDisplay::displayText(data.m_I_orig, data.m_ipLegend + data.m_legendOffset, "A click to continue.", data.m_colorLegend); vpDisplay::flush(data.m_I_orig); vpDisplay::getClick(data.m_I_orig, waitForClick); @@ -366,7 +366,7 @@ class vpTutoAverageFunctor */ vpColVector averagePolynomials(const std::vector &particles, const std::vector &weights, const vpParticleFilter>::vpStateAddFunction &/**/) { - const unsigned int nbParticles = particles.size(); + const unsigned int nbParticles = static_cast(particles.size()); const double nbParticlesAsDOuble = static_cast(nbParticles); // Compute the sum of the weights to be able to determine the "importance" of a particle with regard to the whole set const double sumWeight = std::accumulate(weights.begin(), weights.end(), 0.); @@ -450,7 +450,7 @@ class vpTutoLikelihoodFunctor double likelihood(const vpColVector &coeffs, const std::vector &meas) { double likelihood = 0.; - unsigned int nbPoints = meas.size(); + unsigned int nbPoints = static_cast(meas.size()); // Generate a model from the coefficients stored in the particle state vpTutoParabolaModel model(coeffs, m_height, m_width); @@ -492,8 +492,8 @@ int main(const int argc, const char *argv[]) if (returnCode != tutorial::vpTutoCommonData::SOFTWARE_CONTINUE) { return returnCode; } - const unsigned int vertOffset = data.m_legendOffset.get_i(); - const unsigned int horOffset = data.m_ipLegend.get_j(); + const unsigned int vertOffset = static_cast(data.m_legendOffset.get_i()); + const unsigned int horOffset = static_cast(data.m_ipLegend.get_j()); const unsigned int legendPFVert = data.m_I_orig.getHeight() - 2 * vertOffset, legendPFHor = horOffset; // Initialize the attributes of the PF @@ -511,9 +511,9 @@ int main(const int argc, const char *argv[]) stdevsPF.push_back(ampliMax / 3.); } unsigned long seedPF; // Seed for the random generators of the PF - const float period = 33.3; // 33.3ms i.e. 30Hz + const float period = 33.3f; // 33.3ms i.e. 30Hz if (data.m_pfSeed < 0) { - seedPF = vpTime::measureTimeMicros(); + seedPF = static_cast(vpTime::measureTimeMicros()); } else { seedPF = data.m_pfSeed; @@ -543,8 +543,8 @@ int main(const int argc, const char *argv[]) //! [Init_plot] #ifdef VISP_HAVE_DISPLAY unsigned int plotHeight = 350, plotWidth = 350; - int plotXpos = data.m_legendOffset.get_u(); - int plotYpos = data.m_I_orig.getHeight() + 4. * data.m_legendOffset.get_v(); + int plotXpos = static_cast(data.m_legendOffset.get_u()); + int plotYpos = static_cast(data.m_I_orig.getHeight() + 4. * data.m_legendOffset.get_v()); vpPlot plot(1, plotHeight, plotWidth, plotXpos, plotYpos, "Root mean-square error"); plot.initGraph(0, 1); plot.setLegend(0, 0, "PF estimator"); @@ -587,7 +587,7 @@ int main(const int argc, const char *argv[]) //! [Get_filtered_state] //! [Evaluate_performances] - float pfError = tutorial::evaluate(Xest, data.m_I_orig.getHeight(), data.m_I_orig.getWidth(), edgePoints); + double pfError = tutorial::evaluate(Xest, data.m_I_orig.getHeight(), data.m_I_orig.getWidth(), edgePoints); //! [Evaluate_performances] std::cout << " [Particle Filter method] " << std::endl; std::cout << " Coeffs = [" << Xest.transpose() << " ]" << std::endl; diff --git a/tutorial/particle-filter-curve-fitting/vpTutoMeanSquareFitting.cpp b/tutorial/particle-filter-curve-fitting/vpTutoMeanSquareFitting.cpp index a357909b52..6be7333604 100644 --- a/tutorial/particle-filter-curve-fitting/vpTutoMeanSquareFitting.cpp +++ b/tutorial/particle-filter-curve-fitting/vpTutoMeanSquareFitting.cpp @@ -40,8 +40,8 @@ using namespace VISP_NAMESPACE_NAME; vpTutoMeanSquareFitting::vpTutoMeanSquareFitting(const unsigned int °ree, const unsigned int &height, const unsigned int &width) : m_degree(degree) - , m_height(static_cast(height)) - , m_width(static_cast(width)) + , m_height(static_cast(height)) + , m_width(static_cast(width)) , m_model(degree, height, width) , m_isFitted(false) { } @@ -68,7 +68,7 @@ double vpTutoMeanSquareFitting::evaluate(const std::vector &pts) if (!m_isFitted) { throw(vpException(vpException::notInitialized, "fit() has not been called.")); } - unsigned int nbPts = pts.size(); + unsigned int nbPts = static_cast(pts.size()); // Compute the mean absolute error double meanSquareError = 0.f; @@ -93,7 +93,7 @@ double vpTutoMeanSquareFitting::evaluate(const vpImagePoint &pt) return squareError; } -double vpTutoMeanSquareFitting::model(const float &u) +double vpTutoMeanSquareFitting::model(const double &u) { if (!m_isFitted) { throw(vpException(vpException::notInitialized, "fit() has not been called.")); diff --git a/tutorial/particle-filter-curve-fitting/vpTutoMeanSquareFitting.h b/tutorial/particle-filter-curve-fitting/vpTutoMeanSquareFitting.h index 66b771ce83..5e360e1ba4 100644 --- a/tutorial/particle-filter-curve-fitting/vpTutoMeanSquareFitting.h +++ b/tutorial/particle-filter-curve-fitting/vpTutoMeanSquareFitting.h @@ -91,7 +91,7 @@ class vpTutoMeanSquareFitting * the underlying polynomial model. * \return double The v-ccordinate that corresponds to the model. */ - double model(const float &u); + double model(const double &u); #ifdef VISP_HAVE_DISPLAY /** @@ -107,7 +107,7 @@ class vpTutoMeanSquareFitting { unsigned int width = I.getWidth(); for (unsigned int u = 0; u < width; ++u) { - int v = model(u); + int v = static_cast(model(u)); VISP_NAMESPACE_ADDRESSING vpDisplay::displayPoint(I, v, u, color, 1); VISP_NAMESPACE_ADDRESSING vpDisplay::displayText(I, vertPosLegend, horPosLegend, "Least-mean square model", color); } @@ -151,8 +151,8 @@ class vpTutoMeanSquareFitting protected: unsigned int m_degree; /*!< The degree of the curve that is estimated*/ - double m_height; /*!< The height of the input image*/ - double m_width; /*!< The width of the input image*/ + unsigned int m_height; /*!< The height of the input image*/ + unsigned int m_width; /*!< The width of the input image*/ vpTutoParabolaModel m_model; /*!< The model of the curve we try to fit.*/ bool m_isFitted; /*!< Set to true if the fit method has been called.*/ }; diff --git a/tutorial/particle-filter-curve-fitting/vpTutoParabolaModel.h b/tutorial/particle-filter-curve-fitting/vpTutoParabolaModel.h index ba71e2cf9f..b8921fa0c7 100644 --- a/tutorial/particle-filter-curve-fitting/vpTutoParabolaModel.h +++ b/tutorial/particle-filter-curve-fitting/vpTutoParabolaModel.h @@ -48,8 +48,8 @@ class vpTutoParabolaModel public: inline vpTutoParabolaModel(const unsigned int °ree, const unsigned int &height, const unsigned int &width) : m_degree(degree) - , m_height(static_cast(height)) - , m_width(static_cast(width)) + , m_height(static_cast(height)) + , m_width(static_cast(width)) , m_coeffs(degree + 1, 0.) { } @@ -63,8 +63,8 @@ class vpTutoParabolaModel */ inline vpTutoParabolaModel(const VISP_NAMESPACE_ADDRESSING vpColVector &coeffs, const unsigned int &height, const unsigned int &width) : m_degree(coeffs.size() - 1) - , m_height(static_cast(height)) - , m_width(static_cast(width)) + , m_height(static_cast(height)) + , m_width(static_cast(width)) , m_coeffs(coeffs) { } @@ -78,8 +78,8 @@ class vpTutoParabolaModel */ inline vpTutoParabolaModel(const VISP_NAMESPACE_ADDRESSING vpMatrix &coeffs, const unsigned int &height, const unsigned int &width) : m_degree(coeffs.getRows() - 1) - , m_height(static_cast(height)) - , m_width(static_cast(width)) + , m_height(static_cast(height)) + , m_width(static_cast(width)) , m_coeffs(coeffs.getCol(0)) { } @@ -136,7 +136,7 @@ class vpTutoParabolaModel //! [Fill_LMS_system] static void fillSystem(const unsigned int °ree, const double &height, const double &width, const std::vector &pts, VISP_NAMESPACE_ADDRESSING vpMatrix &A, VISP_NAMESPACE_ADDRESSING vpMatrix &b) { - const unsigned int nbPts = pts.size(); + const unsigned int nbPts = static_cast(pts.size()); const unsigned int nbCoeffs = degree + 1; std::vector normalizedPts; // Normalization to avoid numerical instability @@ -165,8 +165,8 @@ class vpTutoParabolaModel private: unsigned int m_degree; /*!< The highest degree of the polynomial.*/ - double m_height; /*!< The height of the input image*/ - double m_width; /*!< The width of the input image*/ + unsigned int m_height; /*!< The height of the input image*/ + unsigned int m_width; /*!< The width of the input image*/ VISP_NAMESPACE_ADDRESSING vpColVector m_coeffs; /*!< The coefficient of the polynomial, where m_coeffs[0] is the offset and m_coeffs[m_degree] is the coefficient applied to the highest degree.*/ }; } diff --git a/tutorial/particle-filter-curve-fitting/vpTutoSegmentation.cpp b/tutorial/particle-filter-curve-fitting/vpTutoSegmentation.cpp index d533494be3..8134317ec2 100644 --- a/tutorial/particle-filter-curve-fitting/vpTutoSegmentation.cpp +++ b/tutorial/particle-filter-curve-fitting/vpTutoSegmentation.cpp @@ -119,13 +119,13 @@ std::vector< VISP_NAMESPACE_ADDRESSING vpImagePoint > extractSkeleton(vpTutoComm std::vector< vpImagePoint > addSaltAndPepperNoise(const std::vector< vpImagePoint > &noisefreePts, vpTutoCommonData &data) { - const unsigned int nbNoiseFreePts = noisefreePts.size(); - const unsigned int nbPtsToAdd = data.m_ratioSaltPepperNoise * nbNoiseFreePts; + const unsigned int nbNoiseFreePts = static_cast(noisefreePts.size()); + const unsigned int nbPtsToAdd = static_cast(data.m_ratioSaltPepperNoise * nbNoiseFreePts); const double width = data.m_Iskeleton.getWidth(); const double height = data.m_Iskeleton.getHeight(); data.m_IskeletonNoisy = data.m_Iskeleton; - vpGaussRand rngX(0.1666, 0.5, vpTime::measureTimeMicros()); - vpGaussRand rngY(0.1666, 0.5, vpTime::measureTimeMicros() + 4224); + vpGaussRand rngX(0.1666, 0.5, static_cast(vpTime::measureTimeMicros())); + vpGaussRand rngY(0.1666, 0.5, static_cast(vpTime::measureTimeMicros() + 4224)); std::vector noisyPts = noisefreePts; for (unsigned int i = 0; i < nbPtsToAdd + 1; ++i) { double uNormalized = rngX(); diff --git a/tutorial/particle-filter/tutorial-pf.cpp b/tutorial/particle-filter/tutorial-pf.cpp index bcb5b48de7..7a22de0f1f 100644 --- a/tutorial/particle-filter/tutorial-pf.cpp +++ b/tutorial/particle-filter/tutorial-pf.cpp @@ -604,7 +604,7 @@ int main(const int argc, const char *argv[]) long seedPF = args.m_seedPF; // Seed for the random generators of the PF const int nbThread = args.m_nbThreads; if (seedPF < 0) { - seedPF = vpTime::measureTimeMicros(); + seedPF = static_cast(vpTime::measureTimeMicros()); } //! [Constants_for_the_PF] diff --git a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-full.cpp b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-full.cpp index 6ce2f7e2a5..e0019d148f 100644 --- a/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-full.cpp +++ b/tutorial/tracking/model-based/generic/tutorial-mb-generic-tracker-full.cpp @@ -42,7 +42,7 @@ int main(int argc, char **argv) bool opt_display_scale_auto = false; vpColVector opt_dof_to_estimate(6, 1.); // Here we consider 6 dof estimation std::string opt_save; -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) std::string opt_save_results; #endif unsigned int thickness = 2; @@ -72,7 +72,7 @@ int main(int argc, char **argv) else if (std::string(argv[i]) == "--save") { opt_save = std::string(argv[++i]); } -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) else if (std::string(argv[i]) == "--save-results") { opt_save_results = std::string(argv[++i]); } @@ -108,7 +108,7 @@ int main(int argc, char **argv) << " [--downscale-img ]" << " [--dof <0/1 0/1 0/1 0/1 0/1 0/1>]" << " [--save ]" -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) << " [--save-results ]" #endif << " [--display-scale-auto]" @@ -157,7 +157,7 @@ int main(int argc, char **argv) << " is created if it doesn't exist." << " Example: \"result/image-%04d.png\"." << std::endl << std::endl -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) << " --save-results " << std::endl << " Name of the npz file containing cMo data estimated from MBT." << std::endl << " When the name contains a folder like in the next example, the folder" << std::endl @@ -206,7 +206,7 @@ int main(int argc, char **argv) vpIoTools::makeDirectory(parent); } } -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) if (!opt_save_results.empty()) { std::string parent = vpIoTools::getParent(opt_save_results); if (!parent.empty()) { @@ -391,7 +391,7 @@ int main(int argc, char **argv) std::cout << "Initialize tracker on image size: " << I.getWidth() << " x " << I.getHeight() << std::endl; std::vector vec_poses; -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) if (!opt_save_results.empty()) { const unsigned int height = I.getHeight(), width = I.getWidth(); visp::cnpy::npz_save(opt_save_results, "height", &height, { 1 }, "w"); @@ -476,7 +476,7 @@ int main(int argc, char **argv) writer->saveFrame(O); } -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) if (!opt_save_results.empty()) { std::vector vec_pose = poseToVec(cMo); vec_poses.insert(vec_poses.end(), vec_pose.begin(), vec_pose.end()); @@ -488,7 +488,7 @@ int main(int argc, char **argv) } vpDisplay::getClick(I); -#ifdef VISP_HAVE_MINIZ +#if defined(VISP_HAVE_MINIZ) && defined(VISP_HAVE_WORKING_REGEX) if (!opt_save_results.empty()) { visp::cnpy::npz_save(opt_save_results, "vec_poses", vec_poses.data(), { static_cast(vec_poses.size()/6), 6 }, "a"); } @@ -510,4 +510,4 @@ int main(int argc, char **argv) std::cout << "Install OpenCV and rebuild ViSP to use this example." << std::endl; #endif return EXIT_SUCCESS; - } +}