diff --git a/modules/core/include/visp3/core/vpHomogeneousMatrix.h b/modules/core/include/visp3/core/vpHomogeneousMatrix.h index acbc3f8fc8..2d290a04f8 100644 --- a/modules/core/include/visp3/core/vpHomogeneousMatrix.h +++ b/modules/core/include/visp3/core/vpHomogeneousMatrix.h @@ -306,6 +306,7 @@ class VISP_EXPORT vpHomogeneousMatrix : public vpArray2D // Conversion helper function to avoid circular dependencies and MSVC errors that are not exported in the DLL void parse_json(const nlohmann::json &j); void convert_to_json(nlohmann::json &j) const; +public: #endif diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index 23bd4661cd..1f9eebcffc 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -313,14 +313,14 @@ template class vpImage bitmap[i * width + j] = v; } - vpImage operator-(const vpImage &B); + vpImage operator-(const vpImage &B) const; //! Copy operator vpImage &operator=(vpImage other); vpImage &operator=(const Type &v); - bool operator==(const vpImage &I); - bool operator!=(const vpImage &I); + bool operator==(const vpImage &I) const; + bool operator!=(const vpImage &I) const; friend std::ostream &operator<< <>(std::ostream &s, const vpImage &I); friend std::ostream &operator<<(std::ostream &s, const vpImage &I); friend std::ostream &operator<<(std::ostream &s, const vpImage &I); @@ -328,7 +328,7 @@ template class vpImage friend std::ostream &operator<<(std::ostream &s, const vpImage &I); // Perform a look-up table transformation - void performLut(const Type (&lut)[256], unsigned int nbThreads = 1); + void performLut(const Type(&lut)[256], unsigned int nbThreads = 1); // Returns a new image that's a quarter size of the current image void quarterSizeImage(vpImage &res) const; @@ -338,8 +338,8 @@ template class vpImage // set the size of the image and initialize it. void resize(unsigned int h, unsigned int w, const Type &val); - void sub(const vpImage &B, vpImage &C); - void sub(const vpImage &A, const vpImage &B, vpImage &C); + void sub(const vpImage &B, vpImage &C) const; + void sub(const vpImage &A, const vpImage &B, vpImage &C) const; void subsample(unsigned int v_scale, unsigned int h_scale, vpImage &sampled) const; friend void swap<>(vpImage &first, vpImage &second); @@ -486,19 +486,19 @@ inline std::ostream &operator<<(std::ostream &s, const vpImage &I) #if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) namespace { -struct ImageLut_Param_t { +struct ImageLut_Param_t +{ unsigned int m_start_index; unsigned int m_end_index; unsigned char m_lut[256]; unsigned char *m_bitmap; - ImageLut_Param_t() : m_start_index(0), m_end_index(0), m_lut(), m_bitmap(NULL) {} + ImageLut_Param_t() : m_start_index(0), m_end_index(0), m_lut(), m_bitmap(NULL) { } ImageLut_Param_t(unsigned int start_index, unsigned int end_index, unsigned char *bitmap) : m_start_index(start_index), m_end_index(end_index), m_lut(), m_bitmap(bitmap) - { - } + { } }; vpThread::Return performLutThread(vpThread::Args args) @@ -554,19 +554,19 @@ vpThread::Return performLutThread(vpThread::Args args) return 0; } -struct ImageLutRGBa_Param_t { +struct ImageLutRGBa_Param_t +{ unsigned int m_start_index; unsigned int m_end_index; vpRGBa m_lut[256]; unsigned char *m_bitmap; - ImageLutRGBa_Param_t() : m_start_index(0), m_end_index(0), m_lut(), m_bitmap(NULL) {} + ImageLutRGBa_Param_t() : m_start_index(0), m_end_index(0), m_lut(), m_bitmap(NULL) { } ImageLutRGBa_Param_t(unsigned int start_index, unsigned int end_index, unsigned char *bitmap) : m_start_index(start_index), m_end_index(end_index), m_lut(), m_bitmap(bitmap) - { - } + { } }; vpThread::Return performLutRGBaThread(vpThread::Args args) @@ -720,7 +720,8 @@ template void vpImage::init(Type *const array, unsigned int h // Copy the image data memcpy(static_cast(bitmap), static_cast(array), (size_t)(npixels * sizeof(Type))); - } else { + } + else { // Copy the address of the array in the bitmap bitmap = array; } @@ -771,8 +772,7 @@ vpImage::vpImage(Type *const array, unsigned int h, unsigned int w, bool c */ template vpImage::vpImage() : bitmap(NULL), display(NULL), npixels(0), width(0), height(0), row(NULL), hasOwnership(true) -{ -} +{ } /*! \brief resize the image : Image initialization @@ -870,7 +870,7 @@ vpImage::vpImage(const vpImage &I) template vpImage::vpImage(vpImage &&I) : bitmap(I.bitmap), display(I.display), npixels(I.npixels), width(I.width), height(I.height), row(I.row), - hasOwnership(I.hasOwnership) + hasOwnership(I.hasOwnership) { I.bitmap = NULL; I.display = NULL; @@ -921,7 +921,8 @@ template <> inline double vpImage::getMaxValue(bool onlyFiniteVal) const if (bitmap[i] > m && vpMath::isFinite(bitmap[i])) m = bitmap[i]; } - } else { + } + else { for (unsigned int i = 0; i < npixels; i++) { if (bitmap[i] > m) m = bitmap[i]; @@ -948,7 +949,8 @@ template <> inline float vpImage::getMaxValue(bool onlyFiniteVal) const if (bitmap[i] > m && vpMath::isFinite(bitmap[i])) m = bitmap[i]; } - } else { + } + else { for (unsigned int i = 0; i < npixels; i++) { if (bitmap[i] > m) m = bitmap[i]; @@ -1006,7 +1008,8 @@ template <> inline double vpImage::getMinValue(bool onlyFiniteVal) const for (unsigned int i = 0; i < npixels; i++) if (bitmap[i] < m && vpMath::isFinite(bitmap[i])) m = bitmap[i]; - } else { + } + else { for (unsigned int i = 0; i < npixels; i++) if (bitmap[i] < m) m = bitmap[i]; @@ -1031,7 +1034,8 @@ template <> inline float vpImage::getMinValue(bool onlyFiniteVal) const for (unsigned int i = 0; i < npixels; i++) if (bitmap[i] < m && vpMath::isFinite(bitmap[i])) m = bitmap[i]; - } else { + } + else { for (unsigned int i = 0; i < npixels; i++) if (bitmap[i] < m) m = bitmap[i]; @@ -1090,7 +1094,8 @@ template <> inline void vpImage::getMinMaxValue(double &min, double &max max = bitmap[i]; } } - } else { + } + else { for (unsigned int i = 0; i < npixels; i++) { if (bitmap[i] < min) min = bitmap[i]; @@ -1126,7 +1131,8 @@ template <> inline void vpImage::getMinMaxValue(float &min, float &max, b max = bitmap[i]; } } - } else { + } + else { for (unsigned int i = 0; i < npixels; i++) { if (bitmap[i] < min) min = bitmap[i]; @@ -1173,7 +1179,8 @@ template <> inline void vpImage::getMinMaxValue(vpRGBf &min, vpRGBf &max max.B = bitmap[i].B; } } - } else { + } + else { for (unsigned int i = 0; i < npixels; i++) { if (bitmap[i].R < min.R) min.R = bitmap[i].R; @@ -1219,7 +1226,7 @@ void vpImage::getMinMaxLoc(vpImagePoint *minLoc, vpImagePoint *maxLoc, Typ { if (npixels == 0) throw(vpException(vpException::fatalError, "Cannot get location of minimum/maximum " - "values of an empty image")); + "values of an empty image")); Type min = bitmap[0], max = bitmap[0]; vpImagePoint minLoc_, maxLoc_; @@ -1285,7 +1292,7 @@ template vpImage &vpImage::operator=(const Type &v) \return true if the images are the same, false otherwise. */ -template bool vpImage::operator==(const vpImage &I) +template bool vpImage::operator==(const vpImage &I) const { if (this->width != I.getWidth()) return false; @@ -1308,7 +1315,7 @@ template bool vpImage::operator==(const vpImage &I) \return true if the images are different, false if they are the same. */ -template bool vpImage::operator!=(const vpImage &I) { return !(*this == I); } +template bool vpImage::operator!=(const vpImage &I) const { return !(*this == I); } /*! Operation A - B (A is unchanged). @@ -1335,7 +1342,7 @@ int main() \sa sub(const vpImage &, const vpImage &, vpImage &) to avoid matrix allocation for each use. */ -template vpImage vpImage::operator-(const vpImage &B) +template vpImage vpImage::operator-(const vpImage &B) const { vpImage C; sub(*this, B, C); @@ -1631,9 +1638,9 @@ template Type vpImage::getValue(double i, double j) const unsigned int jround_1 = (std::min)(width - 1, jround + 1); double value = - (static_cast(row[iround][jround]) * rfrac + static_cast(row[iround_1][jround]) * rratio) * cfrac + - (static_cast(row[iround][jround_1]) * rfrac + static_cast(row[iround_1][jround_1]) * rratio) * - cratio; + (static_cast(row[iround][jround]) * rfrac + static_cast(row[iround_1][jround]) * rratio) * cfrac + + (static_cast(row[iround][jround_1]) * rfrac + static_cast(row[iround_1][jround_1]) * rratio) * + cratio; return static_cast(vpMath::round(value)); } @@ -1663,7 +1670,7 @@ template <> inline double vpImage::getValue(double i, double j) const unsigned int jround_1 = (std::min)(width - 1, jround + 1); return (row[iround][jround] * rfrac + row[iround_1][jround] * rratio) * cfrac + - (row[iround][jround_1] * rfrac + row[iround_1][jround_1] * rratio) * cratio; + (row[iround][jround_1] * rfrac + row[iround_1][jround_1] * rratio) * cratio; } /*! @@ -1704,12 +1711,15 @@ template <> inline unsigned char vpImage::getValue(double i, doub return static_cast((((up & 0x00FF) * rfrac + (down & 0x00FF) * rratio) * cfrac + ((up >> 8) * rfrac + (down >> 8) * rratio) * cratio) >> 32); - } else if (y_ + 1 < height) { + } + else if (y_ + 1 < height) { return static_cast(((row[y_][x_] * rfrac + row[y_ + 1][x_] * rratio)) >> 16); - } else if (x_ + 1 < width) { + } + else if (x_ + 1 < width) { uint16_t up = vpEndian::reinterpret_cast_uchar_to_uint16_LE(bitmap + y_ * width + x_); return static_cast(((up & 0x00FF) * cfrac + (up >> 8) * cratio) >> 16); - } else { + } + else { return row[y_][x_]; } #else @@ -1731,9 +1741,9 @@ template <> inline unsigned char vpImage::getValue(double i, doub unsigned int jround_1 = (std::min)(width - 1, jround + 1); double value = - (static_cast(row[iround][jround]) * rfrac + static_cast(row[iround_1][jround]) * rratio) * cfrac + - (static_cast(row[iround][jround_1]) * rfrac + static_cast(row[iround_1][jround_1]) * rratio) * - cratio; + (static_cast(row[iround][jround]) * rfrac + static_cast(row[iround_1][jround]) * rratio) * cfrac + + (static_cast(row[iround][jround_1]) * rfrac + static_cast(row[iround_1][jround_1]) * rratio) * + cratio; return static_cast(vpMath::round(value)); #endif } @@ -1763,25 +1773,68 @@ template <> inline vpRGBa vpImage::getValue(double i, double j) const unsigned int jround_1 = (std::min)(width - 1, jround + 1); double valueR = - (static_cast(row[iround][jround].R) * rfrac + static_cast(row[iround_1][jround].R) * rratio) * - cfrac + - (static_cast(row[iround][jround_1].R) * rfrac + static_cast(row[iround_1][jround_1].R) * rratio) * - cratio; + (static_cast(row[iround][jround].R) * rfrac + static_cast(row[iround_1][jround].R) * rratio) * + cfrac + + (static_cast(row[iround][jround_1].R) * rfrac + static_cast(row[iround_1][jround_1].R) * rratio) * + cratio; double valueG = - (static_cast(row[iround][jround].G) * rfrac + static_cast(row[iround_1][jround].G) * rratio) * - cfrac + - (static_cast(row[iround][jround_1].G) * rfrac + static_cast(row[iround_1][jround_1].G) * rratio) * - cratio; + (static_cast(row[iround][jround].G) * rfrac + static_cast(row[iround_1][jround].G) * rratio) * + cfrac + + (static_cast(row[iround][jround_1].G) * rfrac + static_cast(row[iround_1][jround_1].G) * rratio) * + cratio; double valueB = - (static_cast(row[iround][jround].B) * rfrac + static_cast(row[iround_1][jround].B) * rratio) * - cfrac + - (static_cast(row[iround][jround_1].B) * rfrac + static_cast(row[iround_1][jround_1].B) * rratio) * - cratio; + (static_cast(row[iround][jround].B) * rfrac + static_cast(row[iround_1][jround].B) * rratio) * + cfrac + + (static_cast(row[iround][jround_1].B) * rfrac + static_cast(row[iround_1][jround_1].B) * rratio) * + cratio; return vpRGBa(static_cast(vpMath::round(valueR)), static_cast(vpMath::round(valueG)), static_cast(vpMath::round(valueB))); } +/*! + \relates vpImage + */ +template <> inline vpRGBf vpImage::getValue(double i, double j) const +{ + if (i < 0 || j < 0 || i + 1 > height || j + 1 > width) { + throw(vpException(vpImageException::notInTheImage, "Pixel outside of the image")); + } + if (height * width == 0) { + throw vpException(vpImageException::notInitializedError, "Empty image!"); + } + + unsigned int iround = static_cast(floor(i)); + unsigned int jround = static_cast(floor(j)); + + double rratio = i - static_cast(iround); + double cratio = j - static_cast(jround); + + double rfrac = 1.0 - rratio; + double cfrac = 1.0 - cratio; + + unsigned int iround_1 = (std::min)(height - 1, iround + 1); + unsigned int jround_1 = (std::min)(width - 1, jround + 1); + + double valueR = + (static_cast(row[iround][jround].R) * rfrac + static_cast(row[iround_1][jround].R) * rratio) * + cfrac + + (static_cast(row[iround][jround_1].R) * rfrac + static_cast(row[iround_1][jround_1].R) * rratio) * + cratio; + double valueG = + (static_cast(row[iround][jround].G) * rfrac + static_cast(row[iround_1][jround].G) * rratio) * + cfrac + + (static_cast(row[iround][jround_1].G) * rfrac + static_cast(row[iround_1][jround_1].G) * rratio) * + cratio; + double valueB = + (static_cast(row[iround][jround].B) * rfrac + static_cast(row[iround_1][jround].B) * rratio) * + cfrac + + (static_cast(row[iround][jround_1].B) * rfrac + static_cast(row[iround_1][jround_1].B) * rratio) * + cratio; + + return vpRGBf(static_cast(valueR), static_cast(valueG), static_cast(valueB)); +} + /*! Retrieves pixel value from an image containing values of type \e Type with sub-pixel accuracy. @@ -1858,6 +1911,21 @@ template <> inline double vpImage::getSum() const return res; } +/** + * \relates vpImage + */ +template <> inline double vpImage::getSum() const +{ + if ((height == 0) || (width == 0)) + return 0.0; + + double res = 0.0; + for (unsigned int i = 0; i < height * width; ++i) { + res += static_cast(bitmap[i].R) + static_cast(bitmap[i].G) + static_cast(bitmap[i].B); + } + return res; +} + /*! Operation C = *this - B. @@ -1887,13 +1955,14 @@ int main() \sa operator-() */ -template void vpImage::sub(const vpImage &B, vpImage &C) +template void vpImage::sub(const vpImage &B, vpImage &C) const { try { if ((this->getHeight() != C.getHeight()) || (this->getWidth() != C.getWidth())) C.resize(this->getHeight(), this->getWidth()); - } catch (const vpException &me) { + } + catch (const vpException &me) { std::cout << me << std::endl; throw; } @@ -1918,13 +1987,14 @@ template void vpImage::sub(const vpImage &B, vpImage void vpImage::sub(const vpImage &A, const vpImage &B, vpImage &C) +template void vpImage::sub(const vpImage &A, const vpImage &B, vpImage &C) const { try { if ((A.getHeight() != C.getHeight()) || (A.getWidth() != C.getWidth())) C.resize(A.getHeight(), A.getWidth()); - } catch (const vpException &me) { + } + catch (const vpException &me) { std::cout << me << std::endl; throw; } @@ -1946,7 +2016,7 @@ template void vpImage::sub(const vpImage &A, const vpIm \sa vpImage::performLut(const vpRGBa (&lut)[256], unsigned int nbThreads) */ -template void vpImage::performLut(const Type (&)[256], unsigned int) +template void vpImage::performLut(const Type(&)[256], unsigned int) { std::cerr << "Not implemented !" << std::endl; } @@ -1961,7 +2031,7 @@ template void vpImage::performLut(const Type (&)[256], unsign intensity to his new value. \param nbThreads : Number of threads to use for the computation. */ -template <> inline void vpImage::performLut(const unsigned char (&lut)[256], unsigned int nbThreads) +template <> inline void vpImage::performLut(const unsigned char(&lut)[256], unsigned int nbThreads) { unsigned int size = getWidth() * getHeight(); unsigned char *ptrStart = (unsigned char *)bitmap; @@ -1984,7 +2054,8 @@ template <> inline void vpImage::performLut(const unsigned char ( *ptrCurrent = lut[*ptrCurrent]; ++ptrCurrent; } - } else { + } + else { #if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) // Multi-threads @@ -2040,7 +2111,7 @@ template <> inline void vpImage::performLut(const unsigned char ( intensity to his new value. \param nbThreads : Number of threads to use for the computation. */ -template <> inline void vpImage::performLut(const vpRGBa (&lut)[256], unsigned int nbThreads) +template <> inline void vpImage::performLut(const vpRGBa(&lut)[256], unsigned int nbThreads) { unsigned int size = getWidth() * getHeight(); unsigned char *ptrStart = (unsigned char *)bitmap; @@ -2071,7 +2142,8 @@ template <> inline void vpImage::performLut(const vpRGBa (&lut)[256], un *ptrCurrent = lut[*ptrCurrent].A; ++ptrCurrent; } - } else { + } + else { #if defined(VISP_HAVE_PTHREAD) || (defined(_WIN32) && !defined(WINRT_8_0)) // Multi-threads std::vector threadpool; diff --git a/modules/core/include/visp3/core/vpMatrix.h b/modules/core/include/visp3/core/vpMatrix.h index 6f4944d061..bb29788554 100644 --- a/modules/core/include/visp3/core/vpMatrix.h +++ b/modules/core/include/visp3/core/vpMatrix.h @@ -157,7 +157,8 @@ class VISP_EXPORT vpMatrix : public vpArray2D Method used to compute the determinant of a square matrix. \sa det() */ - typedef enum { + typedef enum + { LU_DECOMPOSITION /*!< LU decomposition method. */ } vpDetMethod; @@ -166,7 +167,7 @@ class VISP_EXPORT vpMatrix : public vpArray2D Basic constructor of a matrix of double. Number of columns and rows are zero. */ - vpMatrix() : vpArray2D(0, 0) {} + vpMatrix() : vpArray2D(0, 0) { } /*! Constructor that initialize a matrix of double with 0. @@ -174,7 +175,7 @@ class VISP_EXPORT vpMatrix : public vpArray2D \param r : Matrix number of rows. \param c : Matrix number of columns. */ - vpMatrix(unsigned int r, unsigned int c) : vpArray2D(r, c) {} + vpMatrix(unsigned int r, unsigned int c) : vpArray2D(r, c) { } /*! Constructor that initialize a matrix of double with \e val. @@ -183,7 +184,7 @@ class VISP_EXPORT vpMatrix : public vpArray2D \param c : Matrix number of columns. \param val : Each element of the matrix is set to \e val. */ - vpMatrix(unsigned int r, unsigned int c, double val) : vpArray2D(r, c, val) {} + vpMatrix(unsigned int r, unsigned int c, double val) : vpArray2D(r, c, val) { } vpMatrix(const vpMatrix &M, unsigned int r, unsigned int c, unsigned int nrows, unsigned int ncols); /*! @@ -198,9 +199,9 @@ vpRotationMatrix R; vpMatrix M(R); \endcode */ - vpMatrix(const vpArray2D &A) : vpArray2D(A) {} + vpMatrix(const vpArray2D &A) : vpArray2D(A) { } - vpMatrix(const vpMatrix &A) : vpArray2D(A) {} + vpMatrix(const vpMatrix &A) : vpArray2D(A) { } #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpMatrix(vpMatrix &&A); @@ -210,7 +211,7 @@ vpMatrix M(R); #endif //! Destructor (Memory de-allocation) - virtual ~vpMatrix() {} + virtual ~vpMatrix() { } /*! Removes all elements from the matrix (which are destroyed), @@ -582,7 +583,6 @@ vpMatrix M(R); //------------------------------------------------- /** @name Norms */ //@{ - double euclideanNorm() const; double frobeniusNorm() const; double inducedL2Norm() const; double infinityNorm() const; @@ -993,6 +993,8 @@ vpMatrix M(R); //@} #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) + double euclideanNorm() const; + /*! @name Deprecated functions */ @@ -1001,7 +1003,7 @@ vpMatrix M(R); \deprecated Only provided for compatibilty with ViSP previous releases. This function does nothing. */ - vp_deprecated void init() {} + vp_deprecated void init() { } /*! \deprecated You should rather use stack(const vpMatrix &A) diff --git a/modules/core/include/visp3/core/vpPoseVector.h b/modules/core/include/visp3/core/vpPoseVector.h index db66e64b30..e0b79d2f16 100644 --- a/modules/core/include/visp3/core/vpPoseVector.h +++ b/modules/core/include/visp3/core/vpPoseVector.h @@ -306,6 +306,7 @@ class VISP_EXPORT vpPoseVector : public vpArray2D // Conversion helper function to avoid circular dependencies and MSVC errors that are not exported in the DLL void parse_json(const nlohmann::json &j); void convert_to_json(nlohmann::json &j) const; +public: #endif #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) diff --git a/modules/core/src/math/matrix/vpColVector.cpp b/modules/core/src/math/matrix/vpColVector.cpp index e937f3eddc..f6f03daa66 100644 --- a/modules/core/src/math/matrix/vpColVector.cpp +++ b/modules/core/src/math/matrix/vpColVector.cpp @@ -1359,6 +1359,15 @@ void vpColVector::insert(unsigned int i, const vpColVector &v) memcpy(data + i, v.data, sizeof(double) * v.rowNum); } } +void vpColVector::insert(const vpColVector &v, unsigned int i) +{ + if (i + v.size() > this->size()) + throw(vpException(vpException::dimensionError, "Unable to insert a column vector")); + + if (data != NULL && v.data != NULL && v.rowNum > 0) { + memcpy(data + i, v.data, sizeof(double) * v.rowNum); + } +} /*! @@ -1413,7 +1422,8 @@ int vpColVector::print(std::ostream &s, unsigned int length, char const *intro) if (p == std::string::npos) { maxBefore = vpMath::maximum(maxBefore, thislen); // maxAfter remains the same - } else { + } + else { maxBefore = vpMath::maximum(maxBefore, p); maxAfter = vpMath::maximum(maxAfter, thislen - p - 1); } @@ -1446,7 +1456,8 @@ int vpColVector::print(std::ostream &s, unsigned int length, char const *intro) if (p != std::string::npos) { s.width((std::streamsize)maxAfter); s << values[i].substr(p, maxAfter).c_str(); - } else { + } + else { assert(maxAfter > 1); s.width((std::streamsize)maxAfter); s << ".0"; @@ -1584,10 +1595,11 @@ std::ostream &vpColVector::cppPrint(std::ostream &os, const std::string &matrixN if (!octet) { os << matrixName << "[" << i << "] = " << (*this)[i] << "; " << std::endl; - } else { + } + else { for (unsigned int k = 0; k < sizeof(double); ++k) { os << "((unsigned char*)&(" << matrixName << "[" << i << "]) )[" << k << "] = 0x" << std::hex - << (unsigned int)((unsigned char *)&((*this)[i]))[k] << "; " << std::endl; + << (unsigned int)((unsigned char *)&((*this)[i]))[k] << "; " << std::endl; } } } @@ -1711,7 +1723,8 @@ std::ostream &vpColVector::matlabPrint(std::ostream &os) const os << (*this)[i] << ", "; if (this->getRows() != i + 1) { os << ";" << std::endl; - } else { + } + else { os << "]" << std::endl; } } diff --git a/modules/core/src/math/matrix/vpMatrix.cpp b/modules/core/src/math/matrix/vpMatrix.cpp index e2672de885..25979fb4ac 100644 --- a/modules/core/src/math/matrix/vpMatrix.cpp +++ b/modules/core/src/math/matrix/vpMatrix.cpp @@ -238,7 +238,7 @@ std::cout << "M:\n" << M << std::endl; 4 5.5 6 \endcode */ -vpMatrix::vpMatrix(const std::initializer_list &list) : vpArray2D(list) {} +vpMatrix::vpMatrix(const std::initializer_list &list) : vpArray2D(list) { } /*! Construct a matrix from a list of double values. @@ -266,8 +266,7 @@ std::cout << "M:\n" << M << std::endl; */ vpMatrix::vpMatrix(unsigned int nrows, unsigned int ncols, const std::initializer_list &list) : vpArray2D(nrows, ncols, list) -{ -} +{ } /*! Construct a matrix from a list of double values. @@ -291,7 +290,7 @@ std::cout << "M:\n" << M << std::endl; 4 5.5 6 \endcode */ -vpMatrix::vpMatrix(const std::initializer_list > &lists) : vpArray2D(lists) {} +vpMatrix::vpMatrix(const std::initializer_list > &lists) : vpArray2D(lists) { } #endif @@ -488,7 +487,8 @@ void vpMatrix::transpose(vpMatrix &At) const At[j][i] = (*this)[i][j]; } } - } else { + } + else { SimdMatTranspose(data, rowNum, colNum, At.data); } } @@ -539,7 +539,8 @@ void vpMatrix::AAt(vpMatrix &B) const vpMatrix::blas_dgemm(transa, transb, rowNum, rowNum, colNum, alpha, data, colNum, data, colNum, beta, B.data, rowNum); #endif - } else { + } + else { // compute A*A^T for (unsigned int i = 0; i < rowNum; i++) { for (unsigned int j = i; j < rowNum; j++) { @@ -591,7 +592,8 @@ void vpMatrix::AtA(vpMatrix &B) const vpMatrix::blas_dgemm(transa, transb, colNum, colNum, rowNum, alpha, data, colNum, data, colNum, beta, B.data, colNum); #endif - } else { + } + else { for (unsigned int i = 0; i < colNum; i++) { double *Bi = B[i]; for (unsigned int j = 0; j < i; j++) { @@ -973,7 +975,8 @@ void vpMatrix::multMatrixVector(const vpMatrix &A, const vpColVector &v, vpColVe vpMatrix::blas_dgemv(trans, A.colNum, A.rowNum, alpha, A.data, A.colNum, v.data, incr, beta, w.data, incr); #endif - } else { + } + else { w = 0.0; for (unsigned int j = 0; j < A.colNum; j++) { double vj = v[j]; // optimization em 5/12/2006 @@ -1022,7 +1025,8 @@ void vpMatrix::mult2Matrices(const vpMatrix &A, const vpMatrix &B, vpMatrix &C) vpMatrix::blas_dgemm(trans, trans, B.colNum, A.rowNum, A.colNum, alpha, B.data, B.colNum, A.data, A.colNum, beta, C.data, B.colNum); #endif - } else { + } + else { // 5/12/06 some "very" simple optimization to avoid indexation const unsigned int BcolNum = B.colNum; const unsigned int BrowNum = B.rowNum; @@ -1117,7 +1121,8 @@ void vpMatrix::mult2Matrices(const vpMatrix &A, const vpMatrix &B, vpHomogeneous vpMatrix::blas_dgemm(trans, trans, B.colNum, A.rowNum, A.colNum, alpha, B.data, B.colNum, A.data, A.colNum, beta, C.data, B.colNum); #endif - } else { + } + else { // 5/12/06 some "very" simple optimization to avoid indexation const unsigned int BcolNum = B.colNum; const unsigned int BrowNum = B.rowNum; @@ -1255,7 +1260,8 @@ vpMatrix vpMatrix::operator*(const vpVelocityTwistMatrix &V) const vpMatrix::blas_dgemm(trans, trans, V.colNum, rowNum, colNum, alpha, V.data, V.colNum, data, colNum, beta, M.data, M.colNum); #endif - } else { + } + else { SimdMatMulTwist(data, rowNum, V.data, M.data); } @@ -1294,7 +1300,8 @@ vpMatrix vpMatrix::operator*(const vpForceTwistMatrix &V) const vpMatrix::blas_dgemm(trans, trans, V.getCols(), rowNum, colNum, alpha, V.data, V.getCols(), data, colNum, beta, M.data, M.colNum); #endif - } else { + } + else { SimdMatMulTwist(data, rowNum, V.data, M.data); } @@ -2099,7 +2106,7 @@ unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, double svThreshold) const (void)Ap; (void)svThreshold; throw(vpException(vpException::fatalError, "Cannot compute pseudo-inverse. " - "Install Lapack, Eigen3 or OpenCV 3rd party")); + "Install Lapack, Eigen3 or OpenCV 3rd party")); #endif } @@ -2175,7 +2182,7 @@ int vpMatrix::pseudoInverse(vpMatrix &Ap, int rank_in) const (void)Ap; (void)svThreshold; throw(vpException(vpException::fatalError, "Cannot compute pseudo-inverse. " - "Install Lapack, Eigen3 or OpenCV 3rd party")); + "Install Lapack, Eigen3 or OpenCV 3rd party")); #endif } @@ -2240,7 +2247,7 @@ vpMatrix vpMatrix::pseudoInverse(double svThreshold) const #else (void)svThreshold; throw(vpException(vpException::fatalError, "Cannot compute pseudo-inverse. " - "Install Lapack, Eigen3 or OpenCV 3rd party")); + "Install Lapack, Eigen3 or OpenCV 3rd party")); #endif } @@ -2305,7 +2312,7 @@ vpMatrix vpMatrix::pseudoInverse(int rank_in) const #else (void)svThreshold; throw(vpException(vpException::fatalError, "Cannot compute pseudo-inverse. " - "Install Lapack, Eigen3 or OpenCV 3rd party")); + "Install Lapack, Eigen3 or OpenCV 3rd party")); #endif } @@ -2361,7 +2368,8 @@ vpMatrix vpMatrix::pseudoInverseLapack(double svThreshold) const if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -2428,7 +2436,8 @@ unsigned int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, double svThreshold) con if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -2501,7 +2510,8 @@ unsigned int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, double if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -2636,7 +2646,8 @@ unsigned int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, double if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -2704,7 +2715,8 @@ vpMatrix vpMatrix::pseudoInverseLapack(int rank_in) const if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -2778,7 +2790,8 @@ int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, int rank_in) const if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -2859,7 +2872,8 @@ int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, int rank_in) co if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -3000,7 +3014,8 @@ int vpMatrix::pseudoInverseLapack(vpMatrix &Ap, vpColVector &sv, int rank_in, vp if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -3069,7 +3084,8 @@ vpMatrix vpMatrix::pseudoInverseEigen3(double svThreshold) const if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -3136,7 +3152,8 @@ unsigned int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, double svThreshold) con if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -3209,7 +3226,8 @@ unsigned int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, double if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -3344,7 +3362,8 @@ unsigned int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, double if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -3412,7 +3431,8 @@ vpMatrix vpMatrix::pseudoInverseEigen3(int rank_in) const if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -3486,7 +3506,8 @@ int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, int rank_in) const if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -3567,7 +3588,8 @@ int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, int rank_in) co if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -3708,7 +3730,8 @@ int vpMatrix::pseudoInverseEigen3(vpMatrix &Ap, vpColVector &sv, int rank_in, vp if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -3777,7 +3800,8 @@ vpMatrix vpMatrix::pseudoInverseOpenCV(double svThreshold) const if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -3844,7 +3868,8 @@ unsigned int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, double svThreshold) con if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -3917,7 +3942,8 @@ unsigned int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, double if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -4052,7 +4078,8 @@ unsigned int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, double if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -4120,7 +4147,8 @@ vpMatrix vpMatrix::pseudoInverseOpenCV(int rank_in) const if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -4194,7 +4222,8 @@ int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, int rank_in) const if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -4275,7 +4304,8 @@ int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, int rank_in) co if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -4416,7 +4446,8 @@ int vpMatrix::pseudoInverseOpenCV(vpMatrix &Ap, vpColVector &sv, int rank_in, vp if (nrows < ncols) { U.resize(ncols, ncols, true); sv.resize(nrows, false); - } else { + } + else { U.resize(nrows, ncols, false); sv.resize(ncols, false); } @@ -4510,7 +4541,7 @@ unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThr (void)sv; (void)svThreshold; throw(vpException(vpException::fatalError, "Cannot compute pseudo-inverse. " - "Install Lapack, Eigen3 or OpenCV 3rd party")); + "Install Lapack, Eigen3 or OpenCV 3rd party")); #endif } @@ -4593,7 +4624,7 @@ int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in) const (void)sv; (void)svThreshold; throw(vpException(vpException::fatalError, "Cannot compute pseudo-inverse. " - "Install Lapack, Eigen3 or OpenCV 3rd party")); + "Install Lapack, Eigen3 or OpenCV 3rd party")); #endif } /*! @@ -4912,7 +4943,7 @@ unsigned int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, double svThr (void)imAt; (void)kerAt; throw(vpException(vpException::fatalError, "Cannot compute pseudo-inverse. " - "Install Lapack, Eigen3 or OpenCV 3rd party")); + "Install Lapack, Eigen3 or OpenCV 3rd party")); #endif } @@ -4999,7 +5030,7 @@ int main() int rank_out = A.pseudoInverse(A_p, sv, rank_in, imA, imAt, kerAt); if (rank_out != rank_in) { std::cout << "There is a possibility that the pseudo-inverse in wrong." << std::endl; - std::cout << "Are you sure that the matrix rank is " << rank_in << std::endl; +std::cout << "Are you sure that the matrix rank is " << rank_in << std::endl; } A_p.print(std::cout, 10, "A^+ (pseudo-inverse): "); @@ -5018,42 +5049,42 @@ int main() // Reconstruct matrix A from ImA, ImAt, KerAt vpMatrix S(rank, A.getCols()); - for(unsigned int i = 0; i< rank_in; i++) + for (unsigned int i = 0; i< rank_in; i++) S[i][i] = sv[i]; vpMatrix Vt(A.getCols(), A.getCols()); Vt.insert(imAt.t(), 0, 0); Vt.insert(kerAt, rank, 0); (imA * S * Vt).print(std::cout, 10, "Im(A) * S * [Im(A^T) | Ker(A)]^T:"); } - \endcode +\endcode - Once build, the previous example produces the following output: - \code -A: [2,3]= - 2 3 5 - -4 2 3 -A^+ (pseudo-inverse): [3,2]= - 0.117899 -0.190782 - 0.065380 0.039657 - 0.113612 0.052518 +Once build, the previous example produces the following output : +\code +A : [2, 3] = +2 3 5 +-4 2 3 +A^+(pseudo-inverse) : [3, 2] = +0.117899 -0.190782 +0.065380 0.039657 +0.113612 0.052518 Rank in : 2 -Rank out: 2 -Singular values: 6.874359351 4.443330227 -Im(A): [2,2]= - 0.81458 -0.58003 - 0.58003 0.81458 -Im(A^T): [3,2]= - -0.100515 -0.994397 - 0.524244 -0.024967 - 0.845615 -0.102722 -Ker(A): [3,1]= - -0.032738 - -0.851202 - 0.523816 -Im(A) * S * [Im(A^T) | Ker(A)]^T:[2,3]= - 2 3 5 - -4 2 3 - \endcode +Rank out : 2 +Singular values : 6.874359351 4.443330227 +Im(A) : [2, 2] = +0.81458 -0.58003 +0.58003 0.81458 +Im(A^T) : [3, 2] = +-0.100515 -0.994397 +0.524244 -0.024967 +0.845615 -0.102722 +Ker(A) : [3, 1] = +-0.032738 +-0.851202 +0.523816 +Im(A) * S *[Im(A^T) | Ker(A)]^T : [2, 3] = +2 3 5 +-4 2 3 +\endcode */ int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix &imA, vpMatrix &imAt, vpMatrix &kerAt) const @@ -5072,7 +5103,7 @@ int vpMatrix::pseudoInverse(vpMatrix &Ap, vpColVector &sv, int rank_in, vpMatrix (void)imAt; (void)kerAt; throw(vpException(vpException::fatalError, "Cannot compute pseudo-inverse. " - "Install Lapack, Eigen3 or OpenCV 3rd party")); + "Install Lapack, Eigen3 or OpenCV 3rd party")); #endif } @@ -5607,7 +5638,8 @@ int vpMatrix::print(std::ostream &s, unsigned int length, const std::string &int if (p == std::string::npos) { maxBefore = vpMath::maximum(maxBefore, thislen); // maxAfter remains the same - } else { + } + else { maxBefore = vpMath::maximum(maxBefore, p); maxAfter = vpMath::maximum(maxAfter, thislen - p); } @@ -5637,7 +5669,8 @@ int vpMatrix::print(std::ostream &s, unsigned int length, const std::string &int if (p != std::string::npos) { s.width((std::streamsize)maxAfter); s << values[i * n + j].substr(p, maxAfter).c_str(); - } else { + } + else { s.width((std::streamsize)maxAfter); s << ".0"; } @@ -5698,7 +5731,8 @@ std::ostream &vpMatrix::matlabPrint(std::ostream &os) const } if (this->getRows() != i + 1) { os << ";" << std::endl; - } else { + } + else { os << "]" << std::endl; } } @@ -5831,10 +5865,11 @@ std::ostream &vpMatrix::cppPrint(std::ostream &os, const std::string &matrixName for (unsigned int j = 0; j < this->getCols(); ++j) { if (!octet) { os << matrixName << "[" << i << "][" << j << "] = " << (*this)[i][j] << "; " << std::endl; - } else { + } + else { for (unsigned int k = 0; k < sizeof(double); ++k) { os << "((unsigned char*)&(" << matrixName << "[" << i << "][" << j << "]) )[" << k << "] = 0x" << std::hex - << (unsigned int)((unsigned char *)&((*this)[i][j]))[k] << "; " << std::endl; + << (unsigned int)((unsigned char *)&((*this)[i][j]))[k] << "; " << std::endl; } } } @@ -5851,7 +5886,8 @@ void vpMatrix::stack(const vpMatrix &A) { if (rowNum == 0) { *this = A; - } else if (A.getRows() > 0) { + } + else if (A.getRows() > 0) { if (colNum != A.getCols()) { throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx%d) matrix", rowNum, colNum, A.getRows(), A.getCols())); @@ -5882,7 +5918,8 @@ void vpMatrix::stack(const vpRowVector &r) { if (rowNum == 0) { *this = r; - } else { + } + else { if (colNum != r.getCols()) { throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (1x%d) row vector", rowNum, colNum, r.getCols())); @@ -5922,7 +5959,8 @@ void vpMatrix::stack(const vpColVector &c) { if (colNum == 0) { *this = c; - } else { + } + else { if (rowNum != c.getRows()) { throw(vpException(vpException::dimensionError, "Cannot stack (%dx%d) matrix with (%dx1) column vector", rowNum, colNum, c.getRows())); @@ -5961,12 +5999,14 @@ void vpMatrix::insert(const vpMatrix &A, unsigned int r, unsigned int c) if ((r + A.getRows()) <= rowNum && (c + A.getCols()) <= colNum) { if (A.colNum == colNum && data != NULL && A.data != NULL && A.data != data) { memcpy(data + r * colNum, A.data, sizeof(double) * A.size()); - } else if (data != NULL && A.data != NULL && A.data != data) { + } + else if (data != NULL && A.data != NULL && A.data != data) { for (unsigned int i = r; i < (r + A.getRows()); i++) { memcpy(data + i * colNum + c, A.data + (i - r) * A.colNum, sizeof(double) * A.colNum); } } - } else { + } + else { throw vpException(vpException::dimensionError, "Cannot insert (%dx%d) matrix in (%dx%d) matrix at position (%d,%d)", A.getRows(), A.getCols(), rowNum, colNum, r, c); } @@ -6074,7 +6114,7 @@ vpColVector vpMatrix::eigenValues() const #else { throw(vpException(vpException::functionNotImplementedError, "Eigen values computation is not implemented. " - "You should install Lapack 3rd party")); + "You should install Lapack 3rd party")); } #endif return evalue; @@ -6205,7 +6245,7 @@ void vpMatrix::eigenValues(vpColVector &evalue, vpMatrix &evector) const #else { throw(vpException(vpException::functionNotImplementedError, "Eigen values computation is not implemented. " - "You should install Lapack 3rd party")); + "You should install Lapack 3rd party")); } #endif } @@ -6463,7 +6503,8 @@ vpMatrix vpMatrix::expm() const if (colNum != rowNum) { throw(vpException(vpException::dimensionError, "Cannot compute the exponential of a non square (%dx%d) matrix", rowNum, colNum)); - } else { + } + else { #ifdef VISP_HAVE_GSL size_t size_ = rowNum * colNum; double *b = new double[size_]; @@ -6635,7 +6676,8 @@ double vpMatrix::cond(double svThreshold) const if (std::fabs(minsv) > std::numeric_limits::epsilon()) { return maxsv / minsv; - } else { + } + else { return std::numeric_limits::infinity(); } } @@ -6710,7 +6752,8 @@ double vpMatrix::inducedL2Norm() const } } return max; - } else { + } + else { return 0.; } } @@ -6770,7 +6813,7 @@ double vpMatrix::sumSquare() const \sa frobeniusNorm(), infinityNorm(), inducedL2Norm() */ -vp_deprecated double vpMatrix::euclideanNorm() const { return frobeniusNorm(); } +double vpMatrix::euclideanNorm() const { return frobeniusNorm(); } vpMatrix vpMatrix::stackMatrices(const vpColVector &A, const vpColVector &B) { diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h b/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h index 526791d19c..a6c0381932 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureEllipse.h @@ -67,7 +67,7 @@ class VISP_EXPORT vpFeatureEllipse : public vpBasicFeature //! Default constructor. vpFeatureEllipse(); //! Destructor. - virtual ~vpFeatureEllipse() {} + virtual ~vpFeatureEllipse() { } /*! \section Set coordinates @@ -89,8 +89,7 @@ class VISP_EXPORT vpFeatureEllipse : public vpBasicFeature //! compute the error between two visual features from a subset //! a the possible features vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL); - //! compute the error between a visual features and zero - vpColVector error(unsigned int select = FEATURE_ALL); + /*! * Returns the visual feature corresponding to the ellipse centroid coordinate along camera x-axis. diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h b/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h index 8227d84b3f..0067c88104 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureLuminance.h @@ -108,8 +108,6 @@ class VISP_EXPORT vpFeatureLuminance : public vpBasicFeature vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL); void error(const vpBasicFeature &s_star, vpColVector &e); - //! Compute the error between a visual features and zero - vpColVector error(unsigned int select = FEATURE_ALL); double get_Z() const; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h index a394d35946..6d55e9faff 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeaturePoint.h @@ -185,7 +185,7 @@ class VISP_EXPORT vpFeaturePoint : public vpBasicFeature public: vpFeaturePoint(); //! Destructor. - virtual ~vpFeaturePoint() {} + virtual ~vpFeaturePoint() { } void buildFrom(double x, double y, double Z); @@ -197,8 +197,6 @@ class VISP_EXPORT vpFeaturePoint : public vpBasicFeature vpFeaturePoint *duplicate() const; vpColVector error(const vpBasicFeature &s_star, unsigned int select = FEATURE_ALL); - //! Compute the error between a visual features and zero - vpColVector error(unsigned int select = FEATURE_ALL); double get_x() const; @@ -226,7 +224,8 @@ class VISP_EXPORT vpFeaturePoint : public vpBasicFeature /*! @name Deprecated functions */ - typedef enum { + typedef enum + { X = 1, // x coordinates Y = 2 // y coordinates } vpFeaturePointType; diff --git a/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h b/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h index 4ff9923431..b0c24894a7 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeaturePointPolar.h @@ -310,11 +310,6 @@ class VISP_EXPORT vpFeaturePointPolar : public vpBasicFeature static unsigned int selectRho(); static unsigned int selectTheta(); - /*! - @name Deprecated functions - */ - //! compute the error between a visual features and zero - vpColVector error(unsigned int select = FEATURE_ALL); }; #endif diff --git a/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp b/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp index deae05cae2..fe758ff51b 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureEllipse.cpp @@ -79,6 +79,8 @@ void vpFeatureEllipse::init() } vpFeatureEllipse::vpFeatureEllipse() : A(0), B(0), C(0) { init(); } +vpFeatureEllipse::vpFeatureEllipse(double x, double y, double n20, double n11, double n02) { this->buildFrom(x, y, n20, n11, n02); } + //! compute the interaction matrix from a subset a the possible features vpMatrix vpFeatureEllipse::interaction(unsigned int select) @@ -250,7 +252,8 @@ vpColVector vpFeatureEllipse::error(const vpBasicFeature &s_star, unsigned int s e = vpColVector::stack(e, ey); } - } catch (...) { + } + catch (...) { throw; } diff --git a/modules/vs/include/visp3/vs/vpServoData.h b/modules/vs/include/visp3/vs/vpServoData.h index adb27431d1..9d3ea63b95 100644 --- a/modules/vs/include/visp3/vs/vpServoData.h +++ b/modules/vs/include/visp3/vs/vpServoData.h @@ -93,9 +93,6 @@ class VISP_EXPORT vpServoData void open(const std::string &directory); void close(); - void empty(); - void push(); - void display(vpImage &I); }; #endif diff --git a/modules/vs/src/vpServoData.cpp b/modules/vs/src/vpServoData.cpp index 313f22cff6..8d67f81a4f 100644 --- a/modules/vs/src/vpServoData.cpp +++ b/modules/vs/src/vpServoData.cpp @@ -64,7 +64,8 @@ void vpServoData::open(const std::string &directory) s = directory + "/sStar.dat"; sStarFile.open(s.c_str()); - } catch (...) { + } + catch (...) { vpERROR_TRACE("Error caught"); throw; } @@ -99,9 +100,3 @@ void vpServoData::close() sFile.close(); sStarFile.close(); } - -/* - * Local variables: - * c-basic-offset: 2 - * End: - */