From 63373bd6db7830e8d54b542733a2528415cbd17a Mon Sep 17 00:00:00 2001 From: Fabien Spindler Date: Tue, 4 Jun 2024 10:04:09 +0200 Subject: [PATCH] Fix misra C++ quality rules around old cast and remove useless limits header include --- modules/core/include/visp3/core/vpImage.h | 20 ++-- .../core/include/visp3/core/vpImagePoint.h | 1 - modules/core/include/visp3/core/vpIoTools.h | 62 +++++----- modules/core/src/camera/vpXmlParserCamera.cpp | 76 ++++++------ modules/core/src/display/vpDisplay.cpp | 4 +- modules/core/src/display/vpDisplay_impl.h | 10 +- .../core/src/image/vpCannyEdgeDetection.cpp | 7 +- modules/core/src/image/vpImagePoint.cpp | 2 + modules/core/src/math/matrix/vpMatrix_svd.cpp | 1 - modules/core/src/tools/file/basisu_miniz.h | 4 +- modules/core/src/tools/file/vpIoTools.cpp | 68 ++++++----- .../core/test/math/testTranslationVector.cpp | 1 - modules/imgproc/src/vpCLAHE.cpp | 14 ++- modules/imgproc/src/vpThreshold.cpp | 8 +- modules/io/src/video/vpVideoReader.cpp | 1 - modules/tracker/blob/src/dots/vpDot2.cpp | 8 +- modules/tracker/me/src/moving-edges/vpMe.cpp | 8 +- .../tt/src/tools/vpTemplateTrackerZone.cpp | 10 +- .../src/calibration/vpCalibrationTools.cpp | 1 - .../vpHomographyMalis.cpp | 1 - .../src/pose-estimation/vpPoseDementhon.cpp | 4 +- .../vision/src/pose-estimation/vpPoseRGBD.cpp | 5 +- modules/vision/test/pose/testPoseFeatures.cpp | 1 - .../visual-feature/vpFeatureMomentAlpha.cpp | 5 +- .../visual-feature/vpFeatureMomentArea.cpp | 1 - .../vpFeatureMomentAreaNormalized.cpp | 6 +- .../visual-feature/vpFeatureMomentBasic.cpp | 5 +- .../vpFeatureMomentCInvariant.cpp | 6 +- .../vpFeatureMomentCentered.cpp | 5 +- .../vpFeatureMomentGravityCenter.cpp | 6 +- ...vpFeatureMomentGravityCenterNormalized.cpp | 6 +- .../tag/tutorial-apriltag-detector.cpp | 109 +++++++++--------- 32 files changed, 245 insertions(+), 221 deletions(-) diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index 53217a3df3..e41c1d52c3 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -1807,13 +1807,13 @@ template void vpImage::quarterSizeImage(vpImage &res) c */ template void vpImage::doubleSizeImage(vpImage &res) { - int h = height * 2; - int w = width * 2; + unsigned int h = height * 2; + unsigned int w = width * 2; res.resize(h, w); - for (int i = 0; i < h; ++i) { - for (int j = 0; j < w; ++j) { + for (unsigned int i = 0; i < h; ++i) { + for (unsigned int j = 0; j < w; ++j) { res[i][j] = (*this)[i >> 1][j >> 1]; } } @@ -1827,22 +1827,22 @@ template void vpImage::doubleSizeImage(vpImage &res) */ // interpolate pixels B and I - for (int i = 0; i < h; i += 2) { - for (int j = 1; j < (w - 1); j += 2) { + for (unsigned int i = 0; i < h; i += 2) { + for (unsigned int j = 1; j < (w - 1); j += 2) { res[i][j] = (Type)(0.5 * ((*this)[i >> 1][j >> 1] + (*this)[i >> 1][(j >> 1) + 1])); } } // interpolate pixels E and G - for (int i = 1; i < (h - 1); i += 2) { - for (int j = 0; j < w; j += 2) { + for (unsigned int i = 1; i < (h - 1); i += 2) { + for (unsigned int j = 0; j < w; j += 2) { res[i][j] = (Type)(0.5 * ((*this)[i >> 1][j >> 1] + (*this)[(i >> 1) + 1][j >> 1])); } } // interpolate pixel F - for (int i = 1; i < (h - 1); i += 2) { - for (int j = 1; j < (w - 1); j += 2) { + for (unsigned int i = 1; i < (h - 1); i += 2) { + for (unsigned int j = 1; j < (w - 1); j += 2) { res[i][j] = (Type)(0.25 * ((*this)[i >> 1][j >> 1] + (*this)[i >> 1][(j >> 1) + 1] + (*this)[(i >> 1) + 1][j >> 1] + (*this)[(i >> 1) + 1][(j >> 1) + 1])); } diff --git a/modules/core/include/visp3/core/vpImagePoint.h b/modules/core/include/visp3/core/vpImagePoint.h index ea62ff81e4..e8d34d66dc 100644 --- a/modules/core/include/visp3/core/vpImagePoint.h +++ b/modules/core/include/visp3/core/vpImagePoint.h @@ -43,7 +43,6 @@ #include #include // std::fabs -#include // numeric_limits #include #include diff --git a/modules/core/include/visp3/core/vpIoTools.h b/modules/core/include/visp3/core/vpIoTools.h index 61a02bed16..deff6e055b 100644 --- a/modules/core/include/visp3/core/vpIoTools.h +++ b/modules/core/include/visp3/core/vpIoTools.h @@ -63,7 +63,7 @@ static inline unsigned long vp_mz_crc32(unsigned long crc, const unsigned char * { static const unsigned int s_crc32[16] = { 0, 0x1db71064, 0x3b6e20c8, 0x26d930ac, 0x76dc4190, 0x6b6b51f4, 0x4db26158, 0x5005713c, 0xedb88320, 0xf00f9344, 0xd6d6a3e8, 0xcb61b38c, 0x9b64c2b0, 0x86d3d2d4, 0xa00ae278, 0xbdbdf21c }; - unsigned int crcu32 = (unsigned int)crc; + unsigned int crcu32 = static_cast(crc); if (!ptr) return 0; crcu32 = ~crcu32; while (buf_len--) { @@ -274,42 +274,42 @@ template void npz_save(std::string zipname, std::string fname, const //build the local header std::vector local_header; local_header += "PK"; //first part of sig - local_header += (uint16_t)0x0403; //second part of sig - local_header += (uint16_t)20; //min version to extract - local_header += (uint16_t)0; //general purpose bit flag - local_header += (uint16_t)0; //compression method - local_header += (uint16_t)0; //file last mod time - local_header += (uint16_t)0; //file last mod date - local_header += (uint32_t)crc; //crc - local_header += (uint32_t)nbytes; //compressed size - local_header += (uint32_t)nbytes; //uncompressed size - local_header += (uint16_t)fname.size(); //fname length - local_header += (uint16_t)0; //extra field length + local_header += static_cast(0x0403); //second part of sig + local_header += static_cast(20); //min version to extract + local_header += static_cast(0); //general purpose bit flag + local_header += static_cast(0); //compression method + local_header += static_cast(0); //file last mod time + local_header += static_cast(0); //file last mod date + local_header += static_cast(crc); //crc + local_header += static_cast(nbytes); //compressed size + local_header += static_cast(nbytes); //uncompressed size + local_header += static_cast(fname.size()); //fname length + local_header += static_cast(0); //extra field length local_header += fname; //build global header global_header += "PK"; //first part of sig - global_header += (uint16_t)0x0201; //second part of sig - global_header += (uint16_t)20; //version made by + global_header += static_cast(0x0201); //second part of sig + global_header += static_cast(20); //version made by global_header.insert(global_header.end(), local_header.begin()+4, local_header.begin()+30); - global_header += (uint16_t)0; //file comment length - global_header += (uint16_t)0; //disk number where file starts - global_header += (uint16_t)0; //internal file attributes - global_header += (uint32_t)0; //external file attributes - global_header += (uint32_t)global_header_offset; //relative offset of local file header, since it begins where the global header used to begin + global_header += static_cast(0); //file comment length + global_header += static_cast(0); //disk number where file starts + global_header += static_cast(0); //internal file attributes + global_header += static_cast(0); //external file attributes + global_header += static_cast(global_header_offset); //relative offset of local file header, since it begins where the global header used to begin global_header += fname; //build footer std::vector footer; footer += "PK"; //first part of sig - footer += (uint16_t)0x0605; //second part of sig - footer += (uint16_t)0; //number of this disk - footer += (uint16_t)0; //disk where footer starts - footer += (uint16_t)(nrecs+1); //number of records on this disk - footer += (uint16_t)(nrecs+1); //total number of records - footer += (uint32_t)global_header.size(); //nbytes of global headers - footer += (uint32_t)(global_header_offset + nbytes + local_header.size()); //offset of start of global headers, since global header now starts after newly written array - footer += (uint16_t)0; //zip file comment length + footer += static_cast(0x0605); //second part of sig + footer += static_cast(0); //number of this disk + footer += static_cast(0); //disk where footer starts + footer += static_cast(nrecs+1); //number of records on this disk + footer += static_cast(nrecs+1); //total number of records + footer += static_cast(global_header.size()); //nbytes of global headers + footer += static_cast(global_header_offset + nbytes + local_header.size()); //offset of start of global headers, since global header now starts after newly written array + footer += static_cast(0); //zip file comment length //write everything fwrite(&local_header[0], sizeof(char), local_header.size(), fp); @@ -374,11 +374,11 @@ template std::vector create_npy_header(const std::vector header; - header += (char)0x93; + header += static_cast(0x93); header += "NUMPY"; - header += (char)0x01; //major version of numpy format - header += (char)0x00; //minor version of numpy format - header += (uint16_t)dict.size(); + header += static_cast(0x01); //major version of numpy format + header += static_cast(0x00); //minor version of numpy format + header += static_cast(dict.size()); header.insert(header.end(), dict.begin(), dict.end()); return header; diff --git a/modules/core/src/camera/vpXmlParserCamera.cpp b/modules/core/src/camera/vpXmlParserCamera.cpp index a6201cf8e5..f36f126c97 100644 --- a/modules/core/src/camera/vpXmlParserCamera.cpp +++ b/modules/core/src/camera/vpXmlParserCamera.cpp @@ -302,18 +302,18 @@ class vpXmlParserCamera::Impl bool test_subsampling_height = true; if (subsampling_width) { - test_subsampling_width = (abs((int)subsampl_width - (int)subsampling_width_tmp) < - (allowedPixelDiffOnImageSize * (int)(subsampling_width_tmp / subsampling_width))); + test_subsampling_width = (abs(static_cast(subsampl_width) - static_cast(subsampling_width_tmp)) < + (allowedPixelDiffOnImageSize * static_cast(subsampling_width_tmp / subsampling_width))); } if (subsampling_height) { - test_subsampling_height = (abs((int)subsampl_height - (int)subsampling_height_tmp) < - (allowedPixelDiffOnImageSize * (int)(subsampling_height_tmp / subsampling_height))); + test_subsampling_height = (abs(static_cast(subsampl_height) - static_cast(subsampling_height_tmp)) < + (allowedPixelDiffOnImageSize * static_cast(subsampling_height_tmp / subsampling_height))); } // if same name && same projection model && same image size camera already exists, we return SEQUENCE_OK // otherwise it is a new camera that need to be updated and we return SEQUENCE_OK bool same_name = (cam_name.empty() || (cam_name == camera_name_tmp)); - bool same_img_size = (abs((int)im_width - (int)image_width_tmp) < allowedPixelDiffOnImageSize || im_width == 0) && - (abs((int)im_height - (int)image_height_tmp) < allowedPixelDiffOnImageSize || im_height == 0) && + bool same_img_size = (abs(static_cast(im_width) - static_cast(image_width_tmp)) < allowedPixelDiffOnImageSize || im_width == 0) && + (abs(static_cast(im_height) - static_cast(image_height_tmp)) < allowedPixelDiffOnImageSize || im_height == 0) && (test_subsampling_width) && (test_subsampling_height); if (same_name && same_img_size && same_proj_model) { back = SEQUENCE_OK; // Camera exists @@ -332,8 +332,8 @@ class vpXmlParserCamera::Impl } #if 0 if (!((projModelFound == true) && - (abs((int)im_width - (int)image_width_tmp) < allowedPixelDiffOnImageSize || im_width == 0) && - (abs((int)im_height - (int)image_height_tmp) < allowedPixelDiffOnImageSize || im_height == 0) && + (abs(static_cast(im_width) - static_cast(image_width_tmp)) < allowedPixelDiffOnImageSize || im_width == 0) && + (abs(static_cast(im_height) - static_cast(image_height_tmp)) < allowedPixelDiffOnImageSize || im_height == 0) && (test_subsampling_width) && (test_subsampling_height))) { // Same images size, we need to check if the camera have the same name if (!cam_name.empty() && (cam_name != camera_name_tmp)) { @@ -501,8 +501,8 @@ class vpXmlParserCamera::Impl std::vector fixed_distortion_coeffs; - // In case disortion coefficients are missing, we should complete them with 0 values - // Since 0x3FF is 0011|1111|1111 and we are interrested in the most significant 1s shown below + // In case distortion coefficients are missing, we should complete them with 0 values + // Since 0x3FF is 0011|1111|1111 and we are interested in the most significant 1s shown below // -- --- // If we divide by 32 (>> 2^5 : 5 remaining least significant bits), we will have to check 5 bits only int check = validation / 32; @@ -661,21 +661,25 @@ class vpXmlParserCamera::Impl unsigned int im_height, unsigned int subsampl_width = 0, unsigned int subsampl_height = 0) { vpXmlCodeType prop; - - for (pugi::xml_node node = node_.first_child(); node; node = node.next_sibling()) { - if (node.type() != pugi::node_element) - continue; - - if (SEQUENCE_OK != str2xmlcode(node.name(), prop)) { - prop = CODE_XML_OTHER; - } - if (prop == CODE_XML_CAMERA) { - if (SEQUENCE_OK == read_camera_header(node, cam_name, im_width, im_height, subsampl_width, subsampl_height)) { - return node; + pugi::xml_node resNode = pugi::xml_node(); + + pugi::xml_node node = node_.first_child(); + bool hasNotFoundCam = true; + while (node && hasNotFoundCam) { + if (node.type() == pugi::node_element) { + if (SEQUENCE_OK != str2xmlcode(node.name(), prop)) { + prop = CODE_XML_OTHER; + } + if (prop == CODE_XML_CAMERA) { + if (SEQUENCE_OK == read_camera_header(node, cam_name, im_width, im_height, subsampl_width, subsampl_height)) { + resNode = node; + hasNotFoundCam = false; + } } } + node = node.next_sibling(); } - return pugi::xml_node(); + return resNode; } /*! @@ -998,23 +1002,27 @@ class vpXmlParserCamera::Impl pugi::xml_node find_additional_info(const pugi::xml_node &node_) { vpXmlCodeType prop; + pugi::xml_node resNode = pugi::xml_node(); + + pugi::xml_node node = node_.first_child(); + bool hasNotFoundInfo = true; + while (node && hasNotFoundInfo) { + if (node.type() == pugi::node_element) { + if (SEQUENCE_OK != str2xmlcode(node.name(), prop)) { + prop = CODE_XML_OTHER; + } - for (pugi::xml_node node = node_.first_child(); node; node = node.next_sibling()) { - if (node.type() != pugi::node_element) { - continue; - } - - if (SEQUENCE_OK != str2xmlcode(node.name(), prop)) { - prop = CODE_XML_OTHER; + if (prop == CODE_XML_ADDITIONAL_INFO) { + // We found the node + resNode = node; + hasNotFoundInfo = false; + } } - if (prop == CODE_XML_ADDITIONAL_INFO) { - // We found the node - return node; - } + node = node.next_sibling(); } - return pugi::xml_node(); + return resNode; } /*! diff --git a/modules/core/src/display/vpDisplay.cpp b/modules/core/src/display/vpDisplay.cpp index bd61c68bc0..a15b635f6d 100644 --- a/modules/core/src/display/vpDisplay.cpp +++ b/modules/core/src/display/vpDisplay.cpp @@ -38,8 +38,6 @@ \brief Generic class for image display. */ -#include - #include #include #include @@ -327,6 +325,6 @@ void vpDisplay::setDownScalingFactor(vpScaleType scaleType) { if (!m_displayHasBeenInitialized) { m_scaleType = scaleType; -} + } } END_VISP_NAMESPACE diff --git a/modules/core/src/display/vpDisplay_impl.h b/modules/core/src/display/vpDisplay_impl.h index 063be0700d..a9c202fdf3 100644 --- a/modules/core/src/display/vpDisplay_impl.h +++ b/modules/core/src/display/vpDisplay_impl.h @@ -242,7 +242,7 @@ void vp_display_display_ellipse(const vpImage &I, const vpImagePoint ¢ double t = (a - b) / (a + b); t *= t; // t^2 double circumference = (angle / 2.0) * (a + b) * (1.0 + 3.0 * t / (10.0 + sqrt(4.0 - 3.0 * t))); - unsigned int nbpoints = (unsigned int)(floor(circumference / 20)); + unsigned int nbpoints = static_cast(floor(circumference / 20)); if (nbpoints < 10) { nbpoints = 10; } @@ -563,15 +563,15 @@ template void vp_display_display_roi(const vpImage &I, const double left = floor(roi.getLeft()); double roiheight = floor(roi.getHeight()); double roiwidth = floor(roi.getWidth()); - double iheight = (double)(I.getHeight()); - double iwidth = (double)(I.getWidth()); + double iheight = static_cast(I.getHeight()); + double iwidth = static_cast(I.getWidth()); if (top < 0 || top > iheight || left < 0 || left > iwidth || top + roiheight > iheight || left + roiwidth > iwidth) { throw(vpException(vpException::dimensionError, "Region of interest outside of the image")); } if (I.display != nullptr) { - (I.display)->displayImageROI(I, vpImagePoint(top, left), (unsigned int)roiwidth, (unsigned int)roiheight); + (I.display)->displayImageROI(I, vpImagePoint(top, left), static_cast(roiwidth), static_cast(roiheight)); } } @@ -585,7 +585,7 @@ template void vp_display_flush(const vpImage &I) template void vp_display_flush_roi(const vpImage &I, const vpRect &roi) { if (I.display != nullptr) { - (I.display)->flushDisplayROI(roi.getTopLeft(), (unsigned int)roi.getWidth(), (unsigned int)roi.getHeight()); + (I.display)->flushDisplayROI(roi.getTopLeft(), static_cast(roi.getWidth()), static_cast(roi.getHeight())); } } diff --git a/modules/core/src/image/vpCannyEdgeDetection.cpp b/modules/core/src/image/vpCannyEdgeDetection.cpp index e91e73b660..78c26922fa 100644 --- a/modules/core/src/image/vpCannyEdgeDetection.cpp +++ b/modules/core/src/image/vpCannyEdgeDetection.cpp @@ -514,8 +514,9 @@ vpCannyEdgeDetection::recursiveSearchForStrongEdge(const std::pair #include +#include // numeric_limits + BEGIN_VISP_NAMESPACE /*! Check if an image point belongs to a rectangle. diff --git a/modules/core/src/math/matrix/vpMatrix_svd.cpp b/modules/core/src/math/matrix/vpMatrix_svd.cpp index 8170976fde..70c9121778 100644 --- a/modules/core/src/math/matrix/vpMatrix_svd.cpp +++ b/modules/core/src/math/matrix/vpMatrix_svd.cpp @@ -43,7 +43,6 @@ #include // std::fabs #include -#include // numeric_limits #ifdef VISP_HAVE_EIGEN3 #include diff --git a/modules/core/src/tools/file/basisu_miniz.h b/modules/core/src/tools/file/basisu_miniz.h index 187b8c9bfd..7da4b06210 100644 --- a/modules/core/src/tools/file/basisu_miniz.h +++ b/modules/core/src/tools/file/basisu_miniz.h @@ -1661,7 +1661,8 @@ static mz_bool tdefl_compress_lz_codes(tdefl_compressor *d) #define TDEFL_PUT_BITS_FAST(b, l) { bit_buffer |= (((mz_uint64)(b)) << bits_in); bits_in += (l); } flags = 1; - for (pLZ_codes = d->m_lz_code_buf; pLZ_codes < pLZ_code_buf_end; flags >>= 1) { + pLZ_codes = d->m_lz_code_buf; + while (pLZ_codes < pLZ_code_buf_end) { if (flags == 1) flags = *pLZ_codes++ | 0x100; @@ -1712,6 +1713,7 @@ static mz_bool tdefl_compress_lz_codes(tdefl_compressor *d) pOutput_buf += (bits_in >> 3); bit_buffer >>= (bits_in & ~7); bits_in &= 7; + flags >>= 1; } #undef TDEFL_PUT_BITS_FAST diff --git a/modules/core/src/tools/file/vpIoTools.cpp b/modules/core/src/tools/file/vpIoTools.cpp index 10ef55fb71..d60480881d 100644 --- a/modules/core/src/tools/file/vpIoTools.cpp +++ b/modules/core/src/tools/file/vpIoTools.cpp @@ -56,7 +56,7 @@ #include #include #include -#include +#include // numeric_limits #include #include #include @@ -544,7 +544,7 @@ BEGIN_VISP_NAMESPACE /*! Return build informations (OS, compiler, build flags, used 3rd parties...). */ -const std::string &vpIoTools::getBuildInformation() + const std::string &vpIoTools::getBuildInformation() { static std::string build_info = #include "version_string.inc" @@ -1530,7 +1530,8 @@ bool vpIoTools::readConfigVar(const std::string &var, float &value) { bool found = false; unsigned int configvars_size = configVars.size(); - for (unsigned int k = 0; (k < configvars_size) && (found == false); ++k) { + unsigned int k = 0; + while ((k < configvars_size) && (!found)) { if (configVars[k] == var) { if (configValues[k].compare("PI") == 0) { value = static_cast(M_PI); @@ -1546,8 +1547,9 @@ bool vpIoTools::readConfigVar(const std::string &var, float &value) } found = true; } + ++k; } - if (found == false) { + if (!found) { std::cout << var << " not found in config file" << std::endl; } return found; @@ -1564,7 +1566,8 @@ bool vpIoTools::readConfigVar(const std::string &var, double &value) { bool found = false; unsigned int configvars_size = configVars.size(); - for (unsigned int k = 0; (k < configvars_size) && (found == false); ++k) { + unsigned int k = 0; + while ((k < configvars_size) && (!found)) { if (configVars[k] == var) { if (configValues[k].compare("PI") == 0) { value = M_PI; @@ -1580,8 +1583,9 @@ bool vpIoTools::readConfigVar(const std::string &var, double &value) } found = true; } + ++k; } - if (found == false) { + if (!found) { std::cout << var << " not found in config file" << std::endl; } return found; @@ -1599,13 +1603,15 @@ bool vpIoTools::readConfigVar(const std::string &var, int &value) { bool found = false; unsigned int configvars_size = configVars.size(); - for (unsigned int k = 0; (k < configvars_size) && (found == false); ++k) { + unsigned int k = 0; + while ((k < configvars_size) && (!found)) { if (configVars[k] == var) { value = atoi(configValues[k].c_str()); found = true; } + ++k; } - if (found == false) { + if (!found) { std::cout << var << " not found in config file" << std::endl; } return found; @@ -1671,13 +1677,15 @@ bool vpIoTools::readConfigVar(const std::string &var, std::string &value) { bool found = false; unsigned int configvars_size = configVars.size(); - for (unsigned int k = 0; (k < configvars_size) && (found == false); ++k) { + unsigned int k = 0; + while ((k < configvars_size) && (!found)) { if (configVars[k] == var) { value = configValues[k]; found = true; } + ++k; } - if (found == false) { + if (!found) { std::cout << var << " not found in config file" << std::endl; } return found; @@ -1702,7 +1710,8 @@ bool vpIoTools::readConfigVar(const std::string &var, vpArray2D &value, bool found = false; std::string nb; unsigned int configvars_size = configVars.size(); - for (unsigned int k = 0; (k < configvars_size) && (found == false); ++k) { + unsigned int k = 0; + while ((k < configvars_size) && (!found)) { if (configVars[k] == var) { found = true; // resize or not @@ -1732,6 +1741,7 @@ bool vpIoTools::readConfigVar(const std::string &var, vpArray2D &value, } } } + ++k; } if (found == false) { std::cout << var << " not found in config file" << std::endl; @@ -2124,16 +2134,16 @@ std::string vpIoTools::toLowerCase(const std::string &input) out += std::tolower(*it); } return out; -} + } -/** - * @brief Return a upper-case version of the string \b input . - * Numbers and special characters stay the same - * - * @param input The input string for which we want to ensure that all the characters are in upper case. - * @return std::string A upper-case version of the string \b input, where - * numbers and special characters stay the same - */ + /** + * @brief Return a upper-case version of the string \b input . + * Numbers and special characters stay the same + * + * @param input The input string for which we want to ensure that all the characters are in upper case. + * @return std::string A upper-case version of the string \b input, where + * numbers and special characters stay the same + */ std::string vpIoTools::toUpperCase(const std::string &input) { std::string out; @@ -2145,16 +2155,16 @@ std::string vpIoTools::toUpperCase(const std::string &input) out += std::toupper(*it); } return out; -} + } -/*! - Returns the absolute path using realpath() on Unix systems or - GetFullPathName() on Windows systems. \return According to realpath() - manual, returns an absolute pathname that names the same file, whose - resolution does not involve '.', '..', or symbolic links for Unix systems. - According to GetFullPathName() documentation, retrieves the full path of the - specified file for Windows systems. - */ + /*! + Returns the absolute path using realpath() on Unix systems or + GetFullPathName() on Windows systems. \return According to realpath() + manual, returns an absolute pathname that names the same file, whose + resolution does not involve '.', '..', or symbolic links for Unix systems. + According to GetFullPathName() documentation, retrieves the full path of the + specified file for Windows systems. + */ std::string vpIoTools::getAbsolutePathname(const std::string &pathname) { diff --git a/modules/core/test/math/testTranslationVector.cpp b/modules/core/test/math/testTranslationVector.cpp index 560aad3b63..5a17acb31d 100644 --- a/modules/core/test/math/testTranslationVector.cpp +++ b/modules/core/test/math/testTranslationVector.cpp @@ -40,7 +40,6 @@ */ #include -#include #include #include diff --git a/modules/imgproc/src/vpCLAHE.cpp b/modules/imgproc/src/vpCLAHE.cpp index 2095ff78d0..32720c800f 100644 --- a/modules/imgproc/src/vpCLAHE.cpp +++ b/modules/imgproc/src/vpCLAHE.cpp @@ -146,10 +146,15 @@ std::vector createTransfer(const std::vector &hist, int limit, std:: clipHistogram(hist, cdfs, limit); int hMin = static_cast(hist.size()) - 1; - for (int i = 0; i < hMin; ++i) { + int stopIdx = hMin; + bool hasNotFoundFirstNotZero = true; + int i = 0; + while ((i < stopIdx) && hasNotFoundFirstNotZero) { if (cdfs[i] != 0) { hMin = i; + hasNotFoundFirstNotZero = false; } + ++i; } int cdf = 0; int hist_size = static_cast(hist.size()); @@ -174,10 +179,15 @@ float transferValue(int v, std::vector &clippedHist) { int clippedHistLength = static_cast(clippedHist.size()); int hMin = clippedHistLength - 1; - for (int i = 0; i::epsilon()); - if (w_b_eq_nul == false) { + if (!w_b_eq_nul) { 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) { + if (!w_f_eq_nul) { // Mean Background / Foreground float mu_B = sum_ip_all[cpt] / static_cast(w_B); @@ -296,6 +297,7 @@ int computeThresholdOtsu(const vpHistogram &hist, unsigned int imageSize) } // else exit the loop } + ++cpt; } return threshold; diff --git a/modules/io/src/video/vpVideoReader.cpp b/modules/io/src/video/vpVideoReader.cpp index 82b86cd097..4f94da9773 100644 --- a/modules/io/src/video/vpVideoReader.cpp +++ b/modules/io/src/video/vpVideoReader.cpp @@ -43,7 +43,6 @@ #include #include #include -#include // numeric_limits BEGIN_VISP_NAMESPACE diff --git a/modules/tracker/blob/src/dots/vpDot2.cpp b/modules/tracker/blob/src/dots/vpDot2.cpp index 35e674a82b..8098cb65ff 100644 --- a/modules/tracker/blob/src/dots/vpDot2.cpp +++ b/modules/tracker/blob/src/dots/vpDot2.cpp @@ -2359,16 +2359,20 @@ vpMatrix vpDot2::defineDots(vpDot2 dot[], const unsigned int &n, const std::stri vpDisplay::flush(I); // check that dots are far away ones from the other - for (i = 0; ((i < n) && fromFile); ++i) { + i = 0; + while ((i < n) && fromFile) { double d = sqrt(vpMath::sqr(dot[i].getHeight()) + vpMath::sqr(dot[i].getWidth())); - for (unsigned int j = 0; ((j < n) && fromFile); ++j) { + unsigned int j = 0; + while ((j < n) && fromFile) { if (j != i) { if (dot[i].getDistance(dot[j]) < d) { fromFile = false; std::cout << "Dots from file seem incoherent" << std::endl; } } + ++j; } + ++i; } } diff --git a/modules/tracker/me/src/moving-edges/vpMe.cpp b/modules/tracker/me/src/moving-edges/vpMe.cpp index 29c2a9ed58..e4d32d4773 100644 --- a/modules/tracker/me/src/moving-edges/vpMe.cpp +++ b/modules/tracker/me/src/moving-edges/vpMe.cpp @@ -197,15 +197,19 @@ static bool clipping(vpPoint2Dt A, vpPoint2Dt B, double Xmin, double Ymin, doubl if (code_P[0] != 0) { n = 0; // c'est P[0] qu'on clippera bit_i = 1; - for (i = 0; !(code_P[0] & bit_i); ++i) { + i = 0; + while (!(code_P[0] & bit_i)) { bit_i <<= 1; + ++i; } } else { n = 1; // c'est P[1] qu'on clippera bit_i = 1; - for (i = 0; !(code_P[1] & bit_i); ++i) { + i = 0; + while (!(code_P[1] & bit_i)) { bit_i <<= 1; + ++i; } } diff --git a/modules/tracker/tt/src/tools/vpTemplateTrackerZone.cpp b/modules/tracker/tt/src/tools/vpTemplateTrackerZone.cpp index f7a795b5d6..1c50de3e1c 100644 --- a/modules/tracker/tt/src/tools/vpTemplateTrackerZone.cpp +++ b/modules/tracker/tt/src/tools/vpTemplateTrackerZone.cpp @@ -33,8 +33,6 @@ * *****************************************************************************/ -#include // numeric_limits - #include #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) @@ -47,11 +45,11 @@ BEGIN_VISP_NAMESPACE /*! Default constructor. */ -vpTemplateTrackerZone::vpTemplateTrackerZone() : Zone(), min_x(-1), min_y(-1), max_x(-1), max_y(-1) { } + vpTemplateTrackerZone::vpTemplateTrackerZone() : Zone(), min_x(-1), min_y(-1), max_x(-1), max_y(-1) { } -/*! - Copy constructor. - */ + /*! + Copy constructor. + */ vpTemplateTrackerZone::vpTemplateTrackerZone(const vpTemplateTrackerZone &z) : Zone(), min_x(-1), min_y(-1), max_x(-1), max_y(-1) { diff --git a/modules/vision/src/calibration/vpCalibrationTools.cpp b/modules/vision/src/calibration/vpCalibrationTools.cpp index 417804f4d5..35ce75a0e5 100644 --- a/modules/vision/src/calibration/vpCalibrationTools.cpp +++ b/modules/vision/src/calibration/vpCalibrationTools.cpp @@ -37,7 +37,6 @@ #include #include // std::fabs -#include // numeric_limits #define DEBUG_LEVEL1 0 #define DEBUG_LEVEL2 0 diff --git a/modules/vision/src/homography-estimation/vpHomographyMalis.cpp b/modules/vision/src/homography-estimation/vpHomographyMalis.cpp index 35bd139a18..863f0c0cb0 100644 --- a/modules/vision/src/homography-estimation/vpHomographyMalis.cpp +++ b/modules/vision/src/homography-estimation/vpHomographyMalis.cpp @@ -47,7 +47,6 @@ #include #include // std::fabs -#include // numeric_limits BEGIN_VISP_NAMESPACE diff --git a/modules/vision/src/pose-estimation/vpPoseDementhon.cpp b/modules/vision/src/pose-estimation/vpPoseDementhon.cpp index bc9cb45f64..d05074fb5c 100644 --- a/modules/vision/src/pose-estimation/vpPoseDementhon.cpp +++ b/modules/vision/src/pose-estimation/vpPoseDementhon.cpp @@ -479,7 +479,8 @@ void vpPose::poseDementhonPlan(vpHomogeneousMatrix &cMo) int nbMaxIter = static_cast(std::max(std::ceil(logNOfSvdThresholdLimit - logNofSvdThresh), 1.)); double svdThreshold = m_dementhonSvThresh; int irank = 0; - for (int i = 0; (i < nbMaxIter) && (!isRankEqualTo3); ++i) { + int i = 0; + while ((i < nbMaxIter) && (!isRankEqualTo3)) { irank = A.pseudoInverse(Ap, sv, svdThreshold, imA, imAt, kAt); if (irank == 3) { isRankEqualTo3 = true; @@ -488,6 +489,7 @@ void vpPose::poseDementhonPlan(vpHomogeneousMatrix &cMo) isRankEqualTo3 = false; svdThreshold *= svdFactorUsedWhenFailure; } + ++i; } if (!isRankEqualTo3) { diff --git a/modules/vision/src/pose-estimation/vpPoseRGBD.cpp b/modules/vision/src/pose-estimation/vpPoseRGBD.cpp index 5aa1176503..93341e04ed 100644 --- a/modules/vision/src/pose-estimation/vpPoseRGBD.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRGBD.cpp @@ -56,7 +56,8 @@ void estimatePlaneEquationSVD(const std::vector &point_cloud_face, vpPla vpColVector normal; double fabs_error_m_prev_error = std::fabs(error - prev_error); - for (unsigned int iter = 0; (iter < max_iter) && (fabs_error_m_prev_error > 1e-6); ++iter) { + unsigned int iter = 0; + while ((iter < max_iter) && (fabs_error_m_prev_error > 1e-6)) { if (iter != 0) { tukey.MEstimator(vpRobust::TUKEY, residues, weights); } @@ -116,6 +117,8 @@ void estimatePlaneEquationSVD(const std::vector &point_cloud_face, vpPla error /= total_w; // evaluate one of the end conditions of the for fabs_error_m_prev_error = std::fabs(error - prev_error); + + ++iter; } // Update final weights diff --git a/modules/vision/test/pose/testPoseFeatures.cpp b/modules/vision/test/pose/testPoseFeatures.cpp index dbd1e59b2b..8dbe26bc50 100644 --- a/modules/vision/test/pose/testPoseFeatures.cpp +++ b/modules/vision/test/pose/testPoseFeatures.cpp @@ -32,7 +32,6 @@ */ #include -#include #include #include diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentAlpha.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentAlpha.cpp index 09e67f7a60..8960635465 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentAlpha.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentAlpha.cpp @@ -38,7 +38,6 @@ #include #include -#include #include BEGIN_VISP_NAMESPACE @@ -51,7 +50,7 @@ BEGIN_VISP_NAMESPACE * - vpMomentCentered * - vpFeatureMomentCentered */ -void vpFeatureMomentAlpha::compute_interaction() + void vpFeatureMomentAlpha::compute_interaction() { bool found_moment_centered; bool found_FeatureMoment_centered; @@ -84,7 +83,7 @@ void vpFeatureMomentAlpha::compute_interaction() * - vpMomentCentered * - vpMomentGravityCenter */ -void vpFeatureMomentAlpha::compute_interaction() + void vpFeatureMomentAlpha::compute_interaction() { bool found_moment_centered; bool found_moment_gravity; diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentArea.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentArea.cpp index 703fa33341..05b264be75 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentArea.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentArea.cpp @@ -36,7 +36,6 @@ * *****************************************************************************/ #include -#include #include // numeric_limits #include #include diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentAreaNormalized.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentAreaNormalized.cpp index a314235435..7cc3c73222 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentAreaNormalized.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentAreaNormalized.cpp @@ -33,7 +33,6 @@ #include #ifdef VISP_MOMENTS_COMBINE_MATRICES -#include #include #include @@ -54,7 +53,7 @@ BEGIN_VISP_NAMESPACE * - vpMomentAreaNormalized * - vpFeatureMomentBasic */ -void vpFeatureMomentAreaNormalized::compute_interaction() + void vpFeatureMomentAreaNormalized::compute_interaction() { bool found_moment_centered; bool found_moment_surface_normalized; @@ -101,7 +100,6 @@ void vpFeatureMomentAreaNormalized::compute_interaction() END_VISP_NAMESPACE #else -#include #include #include @@ -120,7 +118,7 @@ BEGIN_VISP_NAMESPACE * - vpMomentAreaNormalized * - vpMomentGravityCenter */ -void vpFeatureMomentAreaNormalized::compute_interaction() + void vpFeatureMomentAreaNormalized::compute_interaction() { bool found_moment_centered; bool found_moment_surface_normalized; diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentBasic.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentBasic.cpp index a5e545b051..ed5f0dd650 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentBasic.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentBasic.cpp @@ -31,7 +31,6 @@ * Implementation for all supported moment features. */ -#include #include #include #include @@ -46,8 +45,8 @@ BEGIN_VISP_NAMESPACE * \param C_ : Third plane coefficient for a plane equation of the following type Ax+By+C=1/Z. * \param featureMoments : Database of features. */ -vpFeatureMomentBasic::vpFeatureMomentBasic(vpMomentDatabase &data_base, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments) + vpFeatureMomentBasic::vpFeatureMomentBasic(vpMomentDatabase &data_base, double A_, double B_, double C_, + vpFeatureMomentDatabase *featureMoments) : vpFeatureMoment(data_base, A_, B_, C_, featureMoments), order(0) { } diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentCInvariant.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentCInvariant.cpp index c544e36432..35180a6b19 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentCInvariant.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentCInvariant.cpp @@ -40,7 +40,6 @@ #include -#include #include BEGIN_VISP_NAMESPACE @@ -53,7 +52,7 @@ BEGIN_VISP_NAMESPACE * - vpMomentCInvariant * - vpFeatureMomentBasic */ -void vpFeatureMomentCInvariant::compute_interaction() + void vpFeatureMomentCInvariant::compute_interaction() { std::vector LI(16); bool found_moment_centered; @@ -418,7 +417,6 @@ END_VISP_NAMESPACE #include #include -#include #include BEGIN_VISP_NAMESPACE @@ -431,7 +429,7 @@ BEGIN_VISP_NAMESPACE * - vpMomentCInvariant * - vpFeatureMomentBasic */ -void vpFeatureMomentCInvariant::compute_interaction() + void vpFeatureMomentCInvariant::compute_interaction() { // std::vector LI(16); LI.resize(16); // LI made class member diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentCentered.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentCentered.cpp index 3a4a3c300a..2c49892f04 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentCentered.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentCentered.cpp @@ -33,7 +33,6 @@ #include -#include #include #include @@ -53,8 +52,8 @@ BEGIN_VISP_NAMESPACE * \param C_ : Third plane coefficient for a plane equation of the following type Ax+By+C=1/Z. * \param featureMoments : Database of features. */ -vpFeatureMomentCentered::vpFeatureMomentCentered(vpMomentDatabase &moments_, double A_, double B_, double C_, - vpFeatureMomentDatabase *featureMoments) + vpFeatureMomentCentered::vpFeatureMomentCentered(vpMomentDatabase &moments_, double A_, double B_, double C_, + vpFeatureMomentDatabase *featureMoments) : vpFeatureMoment(moments_, A_, B_, C_, featureMoments), order(0) { } diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenter.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenter.cpp index a0484a4c6c..7318c24ffd 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenter.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenter.cpp @@ -35,7 +35,6 @@ #ifdef VISP_MOMENTS_COMBINE_MATRICES -#include #include #include @@ -52,7 +51,7 @@ BEGIN_VISP_NAMESPACE * $ Minimum vpMomentObject order needed to compute this feature: 2. */ -void vpFeatureMomentGravityCenter::compute_interaction() + void vpFeatureMomentGravityCenter::compute_interaction() { bool found_featuremoment_basic; @@ -76,7 +75,6 @@ void vpFeatureMomentGravityCenter::compute_interaction() END_VISP_NAMESPACE #else -#include #include #include @@ -95,7 +93,7 @@ BEGIN_VISP_NAMESPACE * * Minimum vpMomentObject order needed to compute this feature: 2. */ -void vpFeatureMomentGravityCenter::compute_interaction() + void vpFeatureMomentGravityCenter::compute_interaction() { bool found_moment_centered; bool found_moment_gravity; diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenterNormalized.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenterNormalized.cpp index f607f8a1f2..193687eb04 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenterNormalized.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentGravityCenterNormalized.cpp @@ -35,7 +35,6 @@ #ifdef VISP_MOMENTS_COMBINE_MATRICES -#include #include #include @@ -56,7 +55,7 @@ BEGIN_VISP_NAMESPACE * - vpMomentAreaNormalized * - vpFeatureMomentAreaNormalized */ -void vpFeatureMomentGravityCenterNormalized::compute_interaction() + void vpFeatureMomentGravityCenterNormalized::compute_interaction() { bool found_moment_gravity; bool found_moment_surface_normalized; @@ -94,7 +93,6 @@ void vpFeatureMomentGravityCenterNormalized::compute_interaction() END_VISP_NAMESPACE #else -#include #include #include @@ -113,7 +111,7 @@ BEGIN_VISP_NAMESPACE * - vpMomentAreaNormalized * - vpMomentGravityCenter */ -void vpFeatureMomentGravityCenterNormalized::compute_interaction() + void vpFeatureMomentGravityCenterNormalized::compute_interaction() { bool found_moment_surface_normalized; bool found_moment_gravity; diff --git a/tutorial/detection/tag/tutorial-apriltag-detector.cpp b/tutorial/detection/tag/tutorial-apriltag-detector.cpp index 52f39d1aab..737034821c 100644 --- a/tutorial/detection/tag/tutorial-apriltag-detector.cpp +++ b/tutorial/detection/tag/tutorial-apriltag-detector.cpp @@ -2,7 +2,6 @@ //! [Include] #include //! [Include] -#include #include #include #include @@ -11,17 +10,13 @@ int main(int argc, const char **argv) { -//! [Macro defined] + //! [Macro defined] #if defined(VISP_HAVE_APRILTAG) && (defined(VISP_HAVE_X11) || defined(VISP_HAVE_GDI) || defined(VISP_HAVE_OPENCV)) //! [Macro defined] -#ifdef ENABLE_VISP_NAMESPACE - using namespace VISP_NAMESPACE_NAME; -#endif - std::string input_filename = "AprilTag.pgm"; - vpDetectorAprilTag::vpAprilTagFamily tagFamily = vpDetectorAprilTag::TAG_36h11; - vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = vpDetectorAprilTag::HOMOGRAPHY_VIRTUAL_VS; + visp::vpDetectorAprilTag::vpAprilTagFamily tagFamily = visp::vpDetectorAprilTag::TAG_36h11; + visp::vpDetectorAprilTag::vpPoseEstimationMethod poseEstimationMethod = visp::vpDetectorAprilTag::HOMOGRAPHY_VIRTUAL_VS; double tagSize = 0.053; float quad_decimate = 1.0; int nThreads = 1; @@ -34,7 +29,7 @@ int main(int argc, const char **argv) for (int i = 1; i < argc; i++) { if (std::string(argv[i]) == "--pose_method" && i + 1 < argc) { - poseEstimationMethod = (vpDetectorAprilTag::vpPoseEstimationMethod)atoi(argv[i + 1]); + poseEstimationMethod = static_cast(atoi(argv[i + 1])); } else if (std::string(argv[i]) == "--tag_size" && i + 1 < argc) { tagSize = atof(argv[i + 1]); @@ -43,17 +38,19 @@ int main(int argc, const char **argv) input_filename = std::string(argv[i + 1]); } else if (std::string(argv[i]) == "--quad_decimate" && i + 1 < argc) { - quad_decimate = (float)atof(argv[i + 1]); + quad_decimate = static_cast(atof(argv[i + 1])); } else if (std::string(argv[i]) == "--nthreads" && i + 1 < argc) { nThreads = atoi(argv[i + 1]); } +#if defined(VISP_HAVE_PUGIXML) else if (std::string(argv[i]) == "--intrinsic" && i + 1 < argc) { intrinsic_file = std::string(argv[i + 1]); } else if (std::string(argv[i]) == "--camera_name" && i + 1 < argc) { camera_name = std::string(argv[i + 1]); } +#endif else if (std::string(argv[i]) == "--display_tag") { display_tag = true; } @@ -61,10 +58,10 @@ int main(int argc, const char **argv) color_id = atoi(argv[i + 1]); } else if (std::string(argv[i]) == "--thickness" && i + 1 < argc) { - thickness = (unsigned int)atoi(argv[i + 1]); + thickness = static_cast(atoi(argv[i + 1])); } else if (std::string(argv[i]) == "--tag_family" && i + 1 < argc) { - tagFamily = (vpDetectorAprilTag::vpAprilTagFamily)atoi(argv[i + 1]); + tagFamily = static_cast(atoi(argv[i + 1])); } else if (std::string(argv[i]) == "--z_aligned") { z_aligned = true; @@ -88,12 +85,12 @@ int main(int argc, const char **argv) } } - vpCameraParameters cam; + visp::vpCameraParameters cam; cam.initPersProjWithoutDistortion(615.1674805, 615.1675415, 312.1889954, 243.4373779); #if defined(VISP_HAVE_PUGIXML) - vpXmlParserCamera parser; + visp::vpXmlParserCamera parser; if (!intrinsic_file.empty() && !camera_name.empty()) { - parser.parse(cam, intrinsic_file, camera_name, vpCameraParameters::perspectiveProjWithoutDistortion); + parser.parse(cam, intrinsic_file, camera_name, visp::vpCameraParameters::perspectiveProjWithoutDistortion); } #endif @@ -104,52 +101,52 @@ int main(int argc, const char **argv) std::cout << "Z aligned: " << z_aligned << std::endl; try { - vpImage I_color; - vpImageIo::read(I_color, input_filename); - vpImage I; - vpImageConvert::convert(I_color, I); + visp::vpImage I_color; + visp::vpImageIo::read(I_color, input_filename); + visp::vpImage I; + visp::vpImageConvert::convert(I_color, I); #ifdef VISP_HAVE_X11 - vpDisplayX d(I); + visp::vpDisplayX d(I); #elif defined(VISP_HAVE_GDI) - vpDisplayGDI d(I); + visp::vpDisplayGDI d(I); #elif defined(HAVE_OPENCV_HIGHGUI) - vpDisplayOpenCV d(I); + visp::vpDisplayOpenCV d(I); #endif //! [Create AprilTag detector] - vpDetectorAprilTag detector(tagFamily); + visp::vpDetectorAprilTag detector(tagFamily); //! [Create AprilTag detector] //! [AprilTag detector settings] detector.setAprilTagQuadDecimate(quad_decimate); detector.setAprilTagPoseEstimationMethod(poseEstimationMethod); detector.setAprilTagNbThreads(nThreads); - detector.setDisplayTag(display_tag, color_id < 0 ? vpColor::none : vpColor::getColor(color_id), thickness); + detector.setDisplayTag(display_tag, color_id < 0 ? visp::vpColor::none : visp::vpColor::getColor(color_id), thickness); detector.setZAlignedWithCameraAxis(z_aligned); //! [AprilTag detector settings] - vpDisplay::display(I); + visp::vpDisplay::display(I); - double t = vpTime::measureTimeMs(); + double t = visp::vpTime::measureTimeMs(); //! [Detect and compute pose] - std::vector cMo_vec; + std::vector cMo_vec; detector.detect(I, tagSize, cam, cMo_vec); //! [Detect and compute pose] - t = vpTime::measureTimeMs() - t; + t = visp::vpTime::measureTimeMs() - t; std::stringstream ss; ss << "Detection time: " << t << " ms for " << detector.getNbObjects() << " tags"; - vpDisplay::displayText(I, 40, 20, ss.str(), vpColor::red); + visp::vpDisplay::displayText(I, 40, 20, ss.str(), visp::vpColor::red); //! [Parse detected codes] for (size_t i = 0; i < detector.getNbObjects(); i++) { //! [Parse detected codes] //! [Get location] - std::vector p = detector.getPolygon(i); - vpRect bbox = detector.getBBox(i); + std::vector p = detector.getPolygon(i); + visp::vpRect bbox = detector.getBBox(i); //! [Get location] - vpDisplay::displayRectangle(I, bbox, vpColor::green); + visp::vpDisplay::displayRectangle(I, bbox, visp::vpColor::green); //! [Get message] std::string message = detector.getMessage(i); //! [Get message] @@ -159,58 +156,58 @@ int main(int argc, const char **argv) int tag_id = atoi(message.substr(tag_id_pos + 4).c_str()); ss.str(""); ss << "Tag id: " << tag_id; - vpDisplay::displayText(I, (int)(bbox.getTop() - 10), (int)bbox.getLeft(), ss.str(), vpColor::red); + visp::vpDisplay::displayText(I, static_cast(bbox.getTop() - 10), static_cast(bbox.getLeft()), ss.str(), visp::vpColor::red); } //! [Get tag id] for (size_t j = 0; j < p.size(); j++) { - vpDisplay::displayCross(I, p[j], 14, vpColor::red, 3); + visp::vpDisplay::displayCross(I, p[j], 14, visp::vpColor::red, 3); std::ostringstream number; number << j; - vpDisplay::displayText(I, p[j] + vpImagePoint(15, 5), number.str(), vpColor::blue); + visp::vpDisplay::displayText(I, p[j] + visp::vpImagePoint(15, 5), number.str(), visp::vpColor::blue); } } - vpDisplay::displayText(I, 20, 20, "Click to display tag poses", vpColor::red); - vpDisplay::flush(I); - vpDisplay::getClick(I); + visp::vpDisplay::displayText(I, 20, 20, "Click to display tag poses", visp::vpColor::red); + visp::vpDisplay::flush(I); + visp::vpDisplay::getClick(I); - vpDisplay::display(I); + visp::vpDisplay::display(I); //! [Display camera pose for each tag] for (size_t i = 0; i < cMo_vec.size(); i++) { - vpDisplay::displayFrame(I, cMo_vec[i], cam, tagSize / 2, vpColor::none, 3); + visp::vpDisplay::displayFrame(I, cMo_vec[i], cam, tagSize / 2, visp::vpColor::none, 3); } //! [Display camera pose for each tag] - vpDisplay::displayText(I, 20, 20, "Click to quit.", vpColor::red); - vpDisplay::flush(I); - vpDisplay::getClick(I); + visp::vpDisplay::displayText(I, 20, 20, "Click to quit.", visp::vpColor::red); + visp::vpDisplay::flush(I); + visp::vpDisplay::getClick(I); #ifdef VISP_HAVE_X11 - vpDisplayX d2(I_color, 50, 50); + visp::vpDisplayX d2(I_color, 50, 50); #elif defined(VISP_HAVE_GDI) - vpDisplayGDI d2(I_color, 50, 50); + visp::vpDisplayGDI d2(I_color, 50, 50); #elif defined(HAVE_OPENCV_HIGHGUI) - vpDisplayOpenCV d2(I_color, 50, 50); + visp::vpDisplayOpenCV d2(I_color, 50, 50); #endif - // To test the displays on a vpRGBa image - vpDisplay::display(I_color); + // To test the displays on a visp::vpRGBa image + visp::vpDisplay::display(I_color); // Display frames and tags but remove the display of the last element - std::vector > tagsCorners = detector.getTagsCorners(); + std::vector > tagsCorners = detector.getTagsCorners(); tagsCorners.pop_back(); - detector.displayTags(I_color, tagsCorners, vpColor::none, 3); + detector.displayTags(I_color, tagsCorners, visp::vpColor::none, 3); cMo_vec.pop_back(); - detector.displayFrames(I_color, cMo_vec, cam, tagSize / 2, vpColor::none, 3); + detector.displayFrames(I_color, cMo_vec, cam, tagSize / 2, visp::vpColor::none, 3); - vpDisplay::displayText(I_color, 20, 20, "Click to quit.", vpColor::red); - vpDisplay::flush(I_color); - vpDisplay::getClick(I_color); + visp::vpDisplay::displayText(I_color, 20, 20, "Click to quit.", visp::vpColor::red); + visp::vpDisplay::flush(I_color); + visp::vpDisplay::getClick(I_color); } - catch (const vpException &e) { + catch (const visp::vpException &e) { std::cerr << "Catch an exception: " << e.getMessage() << std::endl; -} + } #else (void)argc;