From b0563c2c2291005d894e01ad9eca24826ed9b61a Mon Sep 17 00:00:00 2001 From: rlagneau Date: Mon, 27 May 2024 09:10:23 +0200 Subject: [PATCH] [CORE] Moved back the operators in the visp workspace (see https://stackoverflow.com/questions/171862/namespaces-and-operator-overloading-in-c) --- modules/core/include/visp3/core/vpArray2D.h | 141 ++++++++---------- .../include/visp3/core/vpCameraParameters.h | 5 +- modules/core/include/visp3/core/vpColVector.h | 10 +- modules/core/include/visp3/core/vpColor.h | 17 +-- modules/core/include/visp3/core/vpException.h | 13 +- .../core/include/visp3/core/vpHistogramPeak.h | 13 +- .../include/visp3/core/vpHistogramValey.h | 13 +- modules/core/include/visp3/core/vpImage.h | 44 +++--- .../core/include/visp3/core/vpImagePoint.h | 52 ++----- modules/core/include/visp3/core/vpMatrix.h | 9 +- modules/core/include/visp3/core/vpMoment.h | 13 +- .../core/include/visp3/core/vpMomentAlpha.h | 13 +- .../core/include/visp3/core/vpMomentArea.h | 13 +- .../visp3/core/vpMomentAreaNormalized.h | 13 +- .../core/include/visp3/core/vpMomentBasic.h | 13 +- .../include/visp3/core/vpMomentCInvariant.h | 13 +- .../include/visp3/core/vpMomentCentered.h | 13 +- .../include/visp3/core/vpMomentDatabase.h | 13 +- .../visp3/core/vpMomentGravityCenter.h | 12 +- .../core/vpMomentGravityCenterNormalized.h | 13 +- .../core/include/visp3/core/vpMomentObject.h | 13 +- modules/core/include/visp3/core/vpPlane.h | 13 +- modules/core/include/visp3/core/vpPoint.h | 13 +- modules/core/include/visp3/core/vpRGBa.h | 15 +- modules/core/include/visp3/core/vpRGBf.h | 16 +- modules/core/include/visp3/core/vpRect.h | 16 +- .../include/visp3/core/vpRotationMatrix.h | 9 +- .../include/visp3/core/vpRotationVector.h | 9 +- modules/core/include/visp3/core/vpRowVector.h | 3 +- .../core/src/camera/vpCameraParameters.cpp | 16 +- modules/core/src/display/vpColor.cpp | 12 +- modules/core/src/image/vpImagePoint.cpp | 138 ++++++++--------- modules/core/src/image/vpRGBa.cpp | 10 +- modules/core/src/image/vpRGBf.cpp | 10 +- modules/core/src/math/matrix/vpColVector.cpp | 14 +- modules/core/src/math/matrix/vpMatrix.cpp | 100 ++++++------- modules/core/src/math/matrix/vpRowVector.cpp | 20 +-- .../math/transformation/vpRotationMatrix.cpp | 38 ++--- .../math/transformation/vpRotationVector.cpp | 22 +-- .../core/src/tools/exceptions/vpException.cpp | 8 +- modules/core/src/tools/geometry/vpPlane.cpp | 9 +- modules/core/src/tools/geometry/vpRect.cpp | 10 +- .../src/tools/histogram/vpHistogramPeak.cpp | 8 +- .../src/tools/histogram/vpHistogramValey.cpp | 9 +- .../tracking/forward-projection/vpPoint.cpp | 4 +- .../core/src/tracking/moments/vpMoment.cpp | 10 +- .../src/tracking/moments/vpMomentAlpha.cpp | 10 +- .../src/tracking/moments/vpMomentArea.cpp | 9 +- .../moments/vpMomentAreaNormalized.cpp | 9 +- .../src/tracking/moments/vpMomentBasic.cpp | 11 +- .../tracking/moments/vpMomentCInvariant.cpp | 8 +- .../src/tracking/moments/vpMomentCentered.cpp | 8 +- .../src/tracking/moments/vpMomentDatabase.cpp | 8 +- .../moments/vpMomentGravityCenter.cpp | 8 +- .../vpMomentGravityCenterNormalized.cpp | 8 +- .../src/tracking/moments/vpMomentObject.cpp | 8 +- .../include/visp3/imgproc/vpContours.h | 2 +- .../imgproc/include/visp3/imgproc/vpImgproc.h | 2 +- modules/imgproc/src/vpCLAHE.cpp | 2 +- modules/imgproc/src/vpConnectedComponents.cpp | 2 +- modules/imgproc/src/vpContours.cpp | 2 +- modules/imgproc/src/vpFloodFill.cpp | 2 +- modules/imgproc/src/vpMorph.cpp | 2 +- modules/imgproc/src/vpRetinex.cpp | 2 +- modules/imgproc/src/vpThreshold.cpp | 2 +- .../test/with-dataset/testAutoThreshold.cpp | 38 +++-- .../with-dataset/testConnectedComponents.cpp | 39 +++-- .../test/with-dataset/testContours.cpp | 48 +++--- .../test/with-dataset/testFloodFill.cpp | 66 ++++---- .../imgproc/test/with-dataset/testImgproc.cpp | 16 +- .../tracker/blob/include/visp3/blob/vpDot.h | 14 +- .../tracker/blob/include/visp3/blob/vpDot2.h | 14 +- modules/tracker/blob/src/dots/vpDot.cpp | 10 +- modules/tracker/blob/src/dots/vpDot2.cpp | 8 +- .../tracker/me/include/visp3/me/vpMeSite.h | 14 +- .../tracker/me/src/moving-edges/vpMeSite.cpp | 10 +- .../visp3/visual_features/vpFeatureMoment.h | 13 +- .../vpFeatureMomentCInvariant.h | 24 +-- .../visual_features/vpFeatureMomentCentered.h | 13 +- .../src/visual-feature/vpFeatureMoment.cpp | 12 +- .../vpFeatureMomentCInvariant.cpp | 8 +- .../vpFeatureMomentCentered.cpp | 11 +- modules/vs/include/visp3/vs/vpAdaptiveGain.h | 13 +- modules/vs/src/vpAdaptiveGain.cpp | 10 +- 84 files changed, 563 insertions(+), 914 deletions(-) diff --git a/modules/core/include/visp3/core/vpArray2D.h b/modules/core/include/visp3/core/vpArray2D.h index bf91691201..203d5c7700 100644 --- a/modules/core/include/visp3/core/vpArray2D.h +++ b/modules/core/include/visp3/core/vpArray2D.h @@ -55,9 +55,6 @@ template class vpArray2D; } #endif -template -std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING vpArray2D &A); - #ifdef VISP_HAVE_NLOHMANN_JSON #include //template @@ -623,7 +620,30 @@ template class vpArray2D Writes the given array to the output stream and returns a reference to the output stream. */ - friend std::ostream &::operator<< <>(std::ostream &s, const vpArray2D &A); + friend std::ostream &operator<<(std::ostream &s, const vpArray2D &A) + { + if (A.data == nullptr || A.size() == 0) { + return s; + } + std::ios_base::fmtflags original_flags = s.flags(); + + s.precision(10); + for (unsigned int i = 0; i < A.getRows(); i++) { + for (unsigned int j = 0; j < A.getCols() - 1; j++) { + s << A[i][j] << " "; + } + // We don't add " " after the last row element + s << A[i][A.getCols() - 1]; + // We don't add a \n char on the end of the last array line + if (i < A.getRows() - 1) { + s << std::endl; + } + } + + s.flags(original_flags); // restore s to standard state + + return s; + } vpArray2D hadamard(const vpArray2D &m) const; @@ -910,48 +930,49 @@ template class vpArray2D file.close(); return true; } - /*! - Save an array in a YAML-formatted file. - - \param filename : absolute file name. - \param A : array to be saved in the file. - \param header : optional lines that will be saved at the beginning of the - file. Should be YAML-formatted and will adapt to the indentation if any. - \return Returns true if success. - - Here is an example of outputs. - \code - vpArray2D M(3,4); - vpArray2D::saveYAML("matrix.yml", M, "example: a YAML-formatted header"); - vpArray2D::saveYAML("matrixIndent.yml", M, "example:\n - a YAML-formatted \ - header\n - with inner indentation"); - \endcode - Content of matrix.yml: - \code - example: a YAML-formatted header - rows: 3 - cols: 4 - data: - - [0, 0, 0, 0] - - [0, 0, 0, 0] - - [0, 0, 0, 0] - \endcode - Content of matrixIndent.yml: - \code - example: - - a YAML-formatted header - - with inner indentation - rows: 3 - cols: 4 - data: + /*! + Save an array in a YAML-formatted file. + + \param filename : absolute file name. + \param A : array to be saved in the file. + \param header : optional lines that will be saved at the beginning of the + file. Should be YAML-formatted and will adapt to the indentation if any. + + \return Returns true if success. + + Here is an example of outputs. + \code + vpArray2D M(3,4); + vpArray2D::saveYAML("matrix.yml", M, "example: a YAML-formatted header"); + vpArray2D::saveYAML("matrixIndent.yml", M, "example:\n - a YAML-formatted \ + header\n - with inner indentation"); + \endcode + Content of matrix.yml: + \code + example: a YAML-formatted header + rows: 3 + cols: 4 + data: - [0, 0, 0, 0] - [0, 0, 0, 0] - [0, 0, 0, 0] - \endcode - - \sa loadYAML() - */ + \endcode + Content of matrixIndent.yml: + \code + example: + - a YAML-formatted header + - with inner indentation + rows: 3 + cols: 4 + data: + - [0, 0, 0, 0] + - [0, 0, 0, 0] + - [0, 0, 0, 0] + \endcode + + \sa loadYAML() + */ static bool saveYAML(const std::string &filename, const vpArray2D &A, const char *header = "") { std::fstream file; @@ -1079,42 +1100,6 @@ template class vpArray2D static void insert(const vpArray2D &A, const vpArray2D &B, vpArray2D &C, unsigned int r, unsigned int c); //@} }; -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - -template -std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING vpArray2D &A) -{ - if ((A.data == nullptr) || (A.size() == 0)) { - return s; - } - std::ios_base::fmtflags original_flags = s.flags(); - - s.precision(10); - unsigned int a_rows = A.getRows(); - unsigned int a_cols = A.getCols(); - for (unsigned int i = 0; i < a_rows; ++i) { - for (unsigned int j = 0; j < (a_cols - 1); ++j) { - s << A[i][j] << " "; - } - // We don't add " " after the last row element - s << A[i][a_cols - 1]; - // We don't add a \n char on the end of the last array line - if (i < (a_rows - 1)) { - s << std::endl; - } - } - - s.flags(original_flags); // restore s to standard state - - return s; -} - -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif /*! Return the array min value. diff --git a/modules/core/include/visp3/core/vpCameraParameters.h b/modules/core/include/visp3/core/vpCameraParameters.h index dbcecd0eec..0dbb6969f2 100644 --- a/modules/core/include/visp3/core/vpCameraParameters.h +++ b/modules/core/include/visp3/core/vpCameraParameters.h @@ -59,9 +59,6 @@ class vpCameraParameters; } #endif -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpCameraParameters &cam); - #ifdef VISP_HAVE_NLOHMANN_JSON #include // Forward declaration to have the to_json in the global namespace @@ -438,7 +435,7 @@ class VISP_EXPORT vpMatrix get_K_inverse() const; void printParameters(); - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpCameraParameters &cam); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpCameraParameters &cam); private: static const double DEFAULT_U0_PARAMETER; diff --git a/modules/core/include/visp3/core/vpColVector.h b/modules/core/include/visp3/core/vpColVector.h index ad78bfb146..3581b915aa 100644 --- a/modules/core/include/visp3/core/vpColVector.h +++ b/modules/core/include/visp3/core/vpColVector.h @@ -1481,6 +1481,10 @@ vpColVector: public vpArray2D namespace VISP_NAMESPACE_NAME { #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + /*! * \relates vpColVector * Allows to multiply a scalar by a column vector. @@ -1488,10 +1492,8 @@ namespace VISP_NAMESPACE_NAME #ifndef DOXYGEN_SHOULD_SKIP_THIS VISP_EXPORT #endif -vpColVector operator*(const double &x, const vpColVector &v); -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif +VISP_NAMESPACE_ADDRESSING vpColVector operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpColVector &v); + #ifdef VISP_HAVE_NLOHMANN_JSON inline void to_json(nlohmann::json &j, diff --git a/modules/core/include/visp3/core/vpColor.h b/modules/core/include/visp3/core/vpColor.h index 1bb97a68ab..62ac5bed40 100644 --- a/modules/core/include/visp3/core/vpColor.h +++ b/modules/core/include/visp3/core/vpColor.h @@ -37,19 +37,6 @@ #include #include -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif -class vpColor; -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - -// Forward declaration to ensure that the operators are in the global namespace -bool operator==(const VISP_NAMESPACE_ADDRESSING vpColor &c1, const VISP_NAMESPACE_ADDRESSING vpColor &c2); -bool operator!=(const VISP_NAMESPACE_ADDRESSING vpColor &c1, const VISP_NAMESPACE_ADDRESSING vpColor &c2); - #if defined(ENABLE_VISP_NAMESPACE) namespace VISP_NAMESPACE_NAME { @@ -291,8 +278,8 @@ class VISP_EXPORT vpColor : public vpRGBa /*! Default destructor. */ inline virtual ~vpColor() { } - friend VISP_EXPORT bool ::operator==(const vpColor &c1, const vpColor &c2); - friend VISP_EXPORT bool ::operator!=(const vpColor &c1, const vpColor &c2); + friend VISP_EXPORT bool operator==(const vpColor &c1, const vpColor &c2); + friend VISP_EXPORT bool operator!=(const vpColor &c1, const vpColor &c2); /*! Set a color from its RGB values. diff --git a/modules/core/include/visp3/core/vpException.h b/modules/core/include/visp3/core/vpException.h index 76b68875ae..c210cc5588 100644 --- a/modules/core/include/visp3/core/vpException.h +++ b/modules/core/include/visp3/core/vpException.h @@ -45,17 +45,6 @@ #include #include -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif -class vpException; -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - -// Forward declaration to ensure that the operator is in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpException &art); #if defined(ENABLE_VISP_NAMESPACE) namespace VISP_NAMESPACE_NAME { @@ -144,7 +133,7 @@ class VISP_EXPORT vpException : public std::exception /*! * Print the error structure. */ - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpException &art); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpException &art); protected: //! Contains the error code, see the errorCodeEnum table for details. diff --git a/modules/core/include/visp3/core/vpHistogramPeak.h b/modules/core/include/visp3/core/vpHistogramPeak.h index 9985322224..3f9a438fcf 100644 --- a/modules/core/include/visp3/core/vpHistogramPeak.h +++ b/modules/core/include/visp3/core/vpHistogramPeak.h @@ -44,17 +44,6 @@ #include -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif -class vpHistogramPeak; -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - -std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING vpHistogramPeak &p); - #if defined(ENABLE_VISP_NAMESPACE) namespace VISP_NAMESPACE_NAME { @@ -148,7 +137,7 @@ class VISP_EXPORT vpHistogramPeak //--------------------------------- // Printing //--------------------------------- - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &s, const vpHistogramPeak &p); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &s, const vpHistogramPeak &p); protected: unsigned char level; //! Gray level ot the peak. diff --git a/modules/core/include/visp3/core/vpHistogramValey.h b/modules/core/include/visp3/core/vpHistogramValey.h index c04bc4128c..fbb12375a7 100644 --- a/modules/core/include/visp3/core/vpHistogramValey.h +++ b/modules/core/include/visp3/core/vpHistogramValey.h @@ -43,17 +43,6 @@ #include -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif -class vpHistogramValey; -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - -std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING vpHistogramValey &v); - #if defined(ENABLE_VISP_NAMESPACE) namespace VISP_NAMESPACE_NAME { @@ -146,7 +135,7 @@ class VISP_EXPORT vpHistogramValey : vpHistogramPeak //--------------------------------- // Printing //--------------------------------- - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &s, const vpHistogramValey &v); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &s, const vpHistogramValey &v); }; /* diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index 3055ce4a7f..80bd561b2c 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -73,16 +73,17 @@ namespace VISP_NAMESPACE_NAME class vpDisplay; // Ref: http://en.cppreference.com/w/cpp/language/friend#Template_friends template class vpImage; // forward declare to make function declaration possible + +// declarations +template std::ostream &operator<<(std::ostream &, const vpImage &); + +std::ostream &operator<<(std::ostream &, const vpImage &); +std::ostream &operator<<(std::ostream &, const vpImage &); +std::ostream &operator<<(std::ostream &, const vpImage &); +std::ostream &operator<<(std::ostream &, const vpImage &); #if defined(ENABLE_VISP_NAMESPACE) } #endif -// declarations -template std::ostream &operator<<(std::ostream &, const VISP_NAMESPACE_ADDRESSING vpImage &); - -std::ostream &operator<<(std::ostream &, const VISP_NAMESPACE_ADDRESSING vpImage &); -std::ostream &operator<<(std::ostream &, const VISP_NAMESPACE_ADDRESSING vpImage &); -std::ostream &operator<<(std::ostream &, const VISP_NAMESPACE_ADDRESSING vpImage &); -std::ostream &operator<<(std::ostream &, const VISP_NAMESPACE_ADDRESSING vpImage &); template void swap(VISP_NAMESPACE_ADDRESSING vpImage &first, VISP_NAMESPACE_ADDRESSING vpImage &second); @@ -330,13 +331,13 @@ template class vpImage vpImage &operator=(const Type &v); 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); - 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); + 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); + friend std::ostream &operator<<(std::ostream &s, const vpImage &I); - // Perform a look-up table transformation + // Perform a look-up table transformation void performLut(const Type(&lut)[256], unsigned int nbThreads = 1); // Returns a new image that's a quarter size of the current image @@ -362,11 +363,8 @@ template class vpImage Type **row; ///! points the row pointer array bool hasOwnership; ///! true if this instance owns the bitmap, false otherwise (e.g. copyData=false) }; -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif -template std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING vpImage &I) +template std::ostream &operator<<(std::ostream &s, const vpImage &I) { if (I.bitmap == nullptr) { return s; @@ -391,7 +389,7 @@ template std::ostream &operator<<(std::ostream &s, const VISP_NAMES return s; } -inline std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING vpImage &I) +inline std::ostream &operator<<(std::ostream &s, const vpImage &I) { if (I.bitmap == nullptr) { return s; @@ -419,7 +417,7 @@ inline std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING return s; } -inline std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING vpImage &I) +inline std::ostream &operator<<(std::ostream &s, const vpImage &I) { if (I.bitmap == nullptr) { return s; @@ -447,7 +445,7 @@ inline std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING return s; } -inline std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING vpImage &I) +inline std::ostream &operator<<(std::ostream &s, const vpImage &I) { if (I.bitmap == nullptr) { return s; @@ -476,7 +474,7 @@ inline std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING return s; } -inline std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING vpImage &I) +inline std::ostream &operator<<(std::ostream &s, const vpImage &I) { if (I.bitmap == nullptr) { return s; @@ -634,10 +632,6 @@ void performLutRGBaThread(vpImageLutRGBa_Param_t *imageLut_param) } // namespace #endif -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif /*! \relates vpImage */ diff --git a/modules/core/include/visp3/core/vpImagePoint.h b/modules/core/include/visp3/core/vpImagePoint.h index 2c4acdf8eb..7b87e68b85 100644 --- a/modules/core/include/visp3/core/vpImagePoint.h +++ b/modules/core/include/visp3/core/vpImagePoint.h @@ -51,32 +51,8 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpImagePoint; class vpRect; -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - -// Forward declaration to have the operators in the global namespace when using ViSP namespace -bool operator==(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip2); -bool operator!=(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip2); -VISP_NAMESPACE_ADDRESSING vpImagePoint operator+=(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip2); -VISP_NAMESPACE_ADDRESSING vpImagePoint operator+(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip2); -VISP_NAMESPACE_ADDRESSING vpImagePoint operator+(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, int offset); -VISP_NAMESPACE_ADDRESSING vpImagePoint operator+(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, unsigned int offset); -VISP_NAMESPACE_ADDRESSING vpImagePoint operator+(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, double offset); -VISP_NAMESPACE_ADDRESSING vpImagePoint operator-(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip2); -VISP_NAMESPACE_ADDRESSING vpImagePoint operator-(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, int offset); -VISP_NAMESPACE_ADDRESSING vpImagePoint operator-(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, unsigned int offset); -VISP_NAMESPACE_ADDRESSING vpImagePoint operator-(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, double offset); -VISP_NAMESPACE_ADDRESSING vpImagePoint operator*(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, double scale); -VISP_NAMESPACE_ADDRESSING vpImagePoint operator/(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, double scale); -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip); -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif /*! \class vpImagePoint \ingroup group_core_image @@ -388,20 +364,20 @@ class VISP_EXPORT vpImagePoint static vpRect getBBox(const std::vector &ipVec); static double sqrDistance(const vpImagePoint &iP1, const vpImagePoint &iP2); - friend VISP_EXPORT bool ::operator==(const vpImagePoint &ip1, const vpImagePoint &ip2); - friend VISP_EXPORT bool ::operator!=(const vpImagePoint &ip1, const vpImagePoint &ip2); - friend VISP_EXPORT vpImagePoint(::operator+=)(const vpImagePoint &ip1, const vpImagePoint &ip2); - friend VISP_EXPORT vpImagePoint(::operator+)(const vpImagePoint &ip1, const vpImagePoint &ip2); - friend VISP_EXPORT vpImagePoint(::operator+)(const vpImagePoint &ip1, int offset); - friend VISP_EXPORT vpImagePoint(::operator+)(const vpImagePoint &ip1, unsigned int offset); - friend VISP_EXPORT vpImagePoint(::operator+)(const vpImagePoint &ip1, double offset); - friend VISP_EXPORT vpImagePoint(::operator-)(const vpImagePoint &ip1, const vpImagePoint &ip2); - friend VISP_EXPORT vpImagePoint(::operator-)(const vpImagePoint &ip1, int offset); - friend VISP_EXPORT vpImagePoint(::operator-)(const vpImagePoint &ip1, unsigned int offset); - friend VISP_EXPORT vpImagePoint(::operator-)(const vpImagePoint &ip1, double offset); - friend VISP_EXPORT vpImagePoint(::operator*)(const vpImagePoint &ip1, double scale); - friend VISP_EXPORT vpImagePoint(::operator/)(const vpImagePoint &ip1, double scale); - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpImagePoint &ip); + friend VISP_EXPORT bool operator==(const vpImagePoint &ip1, const vpImagePoint &ip2); + friend VISP_EXPORT bool operator!=(const vpImagePoint &ip1, const vpImagePoint &ip2); + friend VISP_EXPORT vpImagePoint operator+=(const vpImagePoint &ip1, const vpImagePoint &ip2); + friend VISP_EXPORT vpImagePoint operator+(const vpImagePoint &ip1, const vpImagePoint &ip2); + friend VISP_EXPORT vpImagePoint operator+(const vpImagePoint &ip1, int offset); + friend VISP_EXPORT vpImagePoint operator+(const vpImagePoint &ip1, unsigned int offset); + friend VISP_EXPORT vpImagePoint operator+(const vpImagePoint &ip1, double offset); + friend VISP_EXPORT vpImagePoint operator-(const vpImagePoint &ip1, const vpImagePoint &ip2); + friend VISP_EXPORT vpImagePoint operator-(const vpImagePoint &ip1, int offset); + friend VISP_EXPORT vpImagePoint operator-(const vpImagePoint &ip1, unsigned int offset); + friend VISP_EXPORT vpImagePoint operator-(const vpImagePoint &ip1, double offset); + friend VISP_EXPORT vpImagePoint operator*(const vpImagePoint &ip1, double scale); + friend VISP_EXPORT vpImagePoint operator/(const vpImagePoint &ip1, double scale); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpImagePoint &ip); private: double i, j; diff --git a/modules/core/include/visp3/core/vpMatrix.h b/modules/core/include/visp3/core/vpMatrix.h index a469965781..14e2719b07 100644 --- a/modules/core/include/visp3/core/vpMatrix.h +++ b/modules/core/include/visp3/core/vpMatrix.h @@ -1209,11 +1209,12 @@ const __declspec(selectany) unsigned int vpMatrix::m_lapack_min_size_default = 0 __declspec(selectany) unsigned int vpMatrix::m_lapack_min_size = vpMatrix::m_lapack_min_size_default; #endif -#ifndef DOXYGEN_SHOULD_SKIP_THIS -VISP_EXPORT -#endif -vpMatrix operator*(const double &x, const vpMatrix &A); #if defined(ENABLE_VISP_NAMESPACE) } #endif + +#ifndef DOXYGEN_SHOULD_SKIP_THIS +VISP_EXPORT +#endif +VISP_NAMESPACE_ADDRESSING vpMatrix operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpMatrix &A); #endif diff --git a/modules/core/include/visp3/core/vpMoment.h b/modules/core/include/visp3/core/vpMoment.h index 0cffa55a1a..6912504188 100644 --- a/modules/core/include/visp3/core/vpMoment.h +++ b/modules/core/include/visp3/core/vpMoment.h @@ -49,20 +49,9 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpMoment; class vpMomentDatabase; class vpMomentObject; -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMoment &m); -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpMoment * @@ -167,7 +156,7 @@ class VISP_EXPORT vpMoment virtual void printDependencies(std::ostream &os) const; void update(vpMomentObject &object); //@} - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpMoment &m); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMoment &m); }; #if defined(ENABLE_VISP_NAMESPACE) } diff --git a/modules/core/include/visp3/core/vpMomentAlpha.h b/modules/core/include/visp3/core/vpMomentAlpha.h index b45e071d53..f7455c452b 100644 --- a/modules/core/include/visp3/core/vpMomentAlpha.h +++ b/modules/core/include/visp3/core/vpMomentAlpha.h @@ -46,18 +46,7 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpMomentAlpha; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentAlpha &v); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpMomentAlpha * @@ -263,7 +252,7 @@ class VISP_EXPORT vpMomentAlpha : public vpMoment return false; } - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpMomentAlpha &v); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentAlpha &v); void printDependencies(std::ostream &os) const; }; #ifdef ENABLE_VISP_NAMESPACE diff --git a/modules/core/include/visp3/core/vpMomentArea.h b/modules/core/include/visp3/core/vpMomentArea.h index 4a0db73af8..6cc10c437a 100644 --- a/modules/core/include/visp3/core/vpMomentArea.h +++ b/modules/core/include/visp3/core/vpMomentArea.h @@ -40,20 +40,9 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpMomentArea; class vpMomentObject; class vpMomentCentered; // Required for discrete case of vpMomentObject -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentArea &m); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpMomentArea * @@ -81,7 +70,7 @@ class VISP_EXPORT vpMomentArea : public vpMoment const std::string name() const { return "vpMomentArea"; } void printDependencies(std::ostream &os) const; //@} - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpMomentArea &m); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentArea &m); }; #ifdef ENABLE_VISP_NAMESPACE } diff --git a/modules/core/include/visp3/core/vpMomentAreaNormalized.h b/modules/core/include/visp3/core/vpMomentAreaNormalized.h index b394d9977e..31c4d97b98 100644 --- a/modules/core/include/visp3/core/vpMomentAreaNormalized.h +++ b/modules/core/include/visp3/core/vpMomentAreaNormalized.h @@ -44,20 +44,9 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpMomentAreaNormalized; class vpMomentObject; class vpMomentCentered; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentAreaNormalized &v); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpMomentAreaNormalized * @@ -194,7 +183,7 @@ class VISP_EXPORT vpMomentAreaNormalized : public vpMoment * Moment name. */ const std::string name() const { return "vpMomentAreaNormalized"; } - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpMomentAreaNormalized &v); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentAreaNormalized &v); void printDependencies(std::ostream &os) const; }; #ifdef ENABLE_VISP_NAMESPACE diff --git a/modules/core/include/visp3/core/vpMomentBasic.h b/modules/core/include/visp3/core/vpMomentBasic.h index a06bc5259d..c44f4b5790 100644 --- a/modules/core/include/visp3/core/vpMomentBasic.h +++ b/modules/core/include/visp3/core/vpMomentBasic.h @@ -46,18 +46,7 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpMomentBasic; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentBasic &v); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! \class vpMomentBasic @@ -95,7 +84,7 @@ class VISP_EXPORT vpMomentBasic : public vpMoment Moment name. */ const std::string name() const { return "vpMomentBasic"; } - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpMomentBasic &v); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentBasic &v); void printDependencies(std::ostream &os) const; }; #ifdef ENABLE_VISP_NAMESPACE diff --git a/modules/core/include/visp3/core/vpMomentCInvariant.h b/modules/core/include/visp3/core/vpMomentCInvariant.h index a10ee46652..5c490f4a05 100644 --- a/modules/core/include/visp3/core/vpMomentCInvariant.h +++ b/modules/core/include/visp3/core/vpMomentCInvariant.h @@ -49,18 +49,7 @@ namespace VISP_NAMESPACE_NAME #endif class vpMomentCentered; class vpMomentBasic; -class vpMomentCInvariant; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentCInvariant &v); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! \class vpMomentCInvariant @@ -292,7 +281,7 @@ class VISP_EXPORT vpMomentCInvariant : public vpMoment */ inline const std::vector &getMomentVector() const { return values; } - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpMomentCInvariant &v); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentCInvariant &v); }; #ifdef ENABLE_VISP_NAMESPACE } diff --git a/modules/core/include/visp3/core/vpMomentCentered.h b/modules/core/include/visp3/core/vpMomentCentered.h index cf448e1d73..b471d3cd85 100644 --- a/modules/core/include/visp3/core/vpMomentCentered.h +++ b/modules/core/include/visp3/core/vpMomentCentered.h @@ -46,19 +46,8 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpMomentCentered; class vpMomentObject; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentCentered &v); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! \class vpMomentCentered @@ -101,7 +90,7 @@ class VISP_EXPORT vpMomentCentered : public vpMoment */ inline const std::string name() const { return "vpMomentCentered"; } - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpMomentCentered &v); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentCentered &v); void printWithIndices(std::ostream &os) const; void printDependencies(std::ostream &os) const; diff --git a/modules/core/include/visp3/core/vpMomentDatabase.h b/modules/core/include/visp3/core/vpMomentDatabase.h index 036832509d..43bdc97033 100644 --- a/modules/core/include/visp3/core/vpMomentDatabase.h +++ b/modules/core/include/visp3/core/vpMomentDatabase.h @@ -49,19 +49,8 @@ namespace VISP_NAMESPACE_NAME { #endif class vpMoment; -class vpMomentDatabase; class vpMomentObject; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentDatabase &v); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpMomentDatabase * @@ -171,7 +160,7 @@ class VISP_EXPORT vpMomentDatabase //@} friend class vpMoment; - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpMomentDatabase &v); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentDatabase &v); }; #ifdef ENABLE_VISP_NAMESPACE } diff --git a/modules/core/include/visp3/core/vpMomentGravityCenter.h b/modules/core/include/visp3/core/vpMomentGravityCenter.h index 25b5bf46ce..bd26b22a44 100644 --- a/modules/core/include/visp3/core/vpMomentGravityCenter.h +++ b/modules/core/include/visp3/core/vpMomentGravityCenter.h @@ -46,18 +46,8 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpMomentGravityCenter; class vpMomentObject; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentGravityCenter &v); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpMomentGravityCenter * @@ -146,7 +136,7 @@ class VISP_EXPORT vpMomentGravityCenter : public vpMoment const std::string name() const { return "vpMomentGravityCenter"; } void printDependencies(std::ostream &os) const; //@} - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpMomentGravityCenter &v); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentGravityCenter &v); }; #ifdef ENABLE_VISP_NAMESPACE } diff --git a/modules/core/include/visp3/core/vpMomentGravityCenterNormalized.h b/modules/core/include/visp3/core/vpMomentGravityCenterNormalized.h index a3884222b8..cf7d78e70d 100644 --- a/modules/core/include/visp3/core/vpMomentGravityCenterNormalized.h +++ b/modules/core/include/visp3/core/vpMomentGravityCenterNormalized.h @@ -46,19 +46,8 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpMomentGravityCenterNormalized; class vpMomentObject; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentGravityCenterNormalized &v); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpMomentGravityCenterNormalized * @@ -81,7 +70,7 @@ class VISP_EXPORT vpMomentGravityCenterNormalized : public vpMomentGravityCenter //! Moment name. const std::string name() const { return "vpMomentGravityCenterNormalized"; } void printDependencies(std::ostream &os) const; - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpMomentGravityCenterNormalized &v); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentGravityCenterNormalized &v); }; #ifdef ENABLE_VISP_NAMESPACE } diff --git a/modules/core/include/visp3/core/vpMomentObject.h b/modules/core/include/visp3/core/vpMomentObject.h index 3e2ca99935..47dcdd680c 100644 --- a/modules/core/include/visp3/core/vpMomentObject.h +++ b/modules/core/include/visp3/core/vpMomentObject.h @@ -50,18 +50,7 @@ namespace VISP_NAMESPACE_NAME { #endif class vpCameraParameters; -class vpMomentObject; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentObject &v); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! \class vpMomentObject @@ -296,7 +285,7 @@ class VISP_EXPORT vpMomentObject void init(unsigned int orderinp); void init(const vpMomentObject &objin); - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpMomentObject &v); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentObject &v); /*! Outputs raw moments in indexed form like m[1,1] = value of moment m11 \param momobj : A vpMomentObject diff --git a/modules/core/include/visp3/core/vpPlane.h b/modules/core/include/visp3/core/vpPlane.h index bf16976453..180648969c 100644 --- a/modules/core/include/visp3/core/vpPlane.h +++ b/modules/core/include/visp3/core/vpPlane.h @@ -43,18 +43,7 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpPlane; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpPlane &p); -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif /*! \class vpPlane @@ -162,7 +151,7 @@ class VISP_EXPORT vpPlane vpColVector getNormal() const; void getNormal(vpColVector &n) const; - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpPlane &p); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpPlane &p); // Operation with Plane void projectionPointOnPlan(const vpPoint &P, vpPoint &Pproj) const; diff --git a/modules/core/include/visp3/core/vpPoint.h b/modules/core/include/visp3/core/vpPoint.h index 80af46e0f8..6065dafa78 100644 --- a/modules/core/include/visp3/core/vpPoint.h +++ b/modules/core/include/visp3/core/vpPoint.h @@ -48,18 +48,7 @@ namespace VISP_NAMESPACE_NAME { #endif class vpHomogeneousMatrix; -class vpPoint; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpPoint &vpp); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! \class vpPoint \ingroup group_core_geometry @@ -133,7 +122,7 @@ class VISP_EXPORT vpPoint : public vpForwardProjection vpColVector getWorldCoordinates(void); void getWorldCoordinates(std::vector &oP); - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpPoint &vpp); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpPoint &vpp); //! Projection onto the image plane of a point. Input: the 3D coordinates in //! the camera frame _cP, output : the 2D coordinates _p. diff --git a/modules/core/include/visp3/core/vpRGBa.h b/modules/core/include/visp3/core/vpRGBa.h index 89daeb2160..5e690b798f 100644 --- a/modules/core/include/visp3/core/vpRGBa.h +++ b/modules/core/include/visp3/core/vpRGBa.h @@ -48,18 +48,7 @@ namespace VISP_NAMESPACE_NAME { #endif class vpRGBa; -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - -// Forward declaration to have the operators in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpRGBa &rgba); -VISP_NAMESPACE_ADDRESSING vpRGBa operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpRGBa &rgb); -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif /*! \class vpRGBa @@ -149,7 +138,7 @@ class VISP_EXPORT vpRGBa bool operator<(const vpRGBa &v) const; bool operator>(const vpRGBa &v) const; - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpRGBa &rgba); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRGBa &rgba); public: unsigned char R; //!< Red component. @@ -157,7 +146,7 @@ class VISP_EXPORT vpRGBa unsigned char B; //!< Blue component. unsigned char A; //!< Additionnal component. - friend VISP_EXPORT vpRGBa(::operator*)(const double &x, const vpRGBa &rgb); + friend VISP_EXPORT vpRGBa operator*(const double &x, const vpRGBa &rgb); }; #if defined(ENABLE_VISP_NAMESPACE) } diff --git a/modules/core/include/visp3/core/vpRGBf.h b/modules/core/include/visp3/core/vpRGBf.h index 06ab1fbcfe..6823f4fcc3 100644 --- a/modules/core/include/visp3/core/vpRGBf.h +++ b/modules/core/include/visp3/core/vpRGBf.h @@ -47,19 +47,7 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpRGBf; -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpRGBf &rgb); -VISP_NAMESPACE_ADDRESSING vpRGBf operator*(double x, const VISP_NAMESPACE_ADDRESSING vpRGBf &rgb); -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif /*! \class vpRGBf @@ -136,14 +124,14 @@ class VISP_EXPORT vpRGBf bool operator<(const vpRGBf &v) const; bool operator>(const vpRGBf &v) const; - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpRGBf &rgb); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRGBf &rgb); public: float R; //!< Red component. float G; //!< Green component. float B; //!< Blue component. - friend VISP_EXPORT vpRGBf(::operator*)(double x, const vpRGBf &rgb); + friend VISP_EXPORT vpRGBf operator*(double x, const vpRGBf &rgb); }; #if defined(ENABLE_VISP_NAMESPACE) } diff --git a/modules/core/include/visp3/core/vpRect.h b/modules/core/include/visp3/core/vpRect.h index ef1f95ac7e..3bb1e980a0 100644 --- a/modules/core/include/visp3/core/vpRect.h +++ b/modules/core/include/visp3/core/vpRect.h @@ -45,19 +45,7 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpRect; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -bool inRectangle(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip, const VISP_NAMESPACE_ADDRESSING vpRect &rect); -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpRect &r); -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif /*! \class vpRect \ingroup group_core_geometry @@ -283,8 +271,8 @@ class VISP_EXPORT vpRect return a &= r; } - friend VISP_EXPORT bool ::inRectangle(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip, const vpRect &rect); - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpRect &r); + friend VISP_EXPORT bool inRectangle(const vpImagePoint &ip, const vpRect &rect); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRect &r); void set(double left, double top, double width, double height); void set(const vpImagePoint &topLeft, double width, double height); diff --git a/modules/core/include/visp3/core/vpRotationMatrix.h b/modules/core/include/visp3/core/vpRotationMatrix.h index 796b77587b..5a8d80b2b6 100644 --- a/modules/core/include/visp3/core/vpRotationMatrix.h +++ b/modules/core/include/visp3/core/vpRotationMatrix.h @@ -231,11 +231,12 @@ class VISP_EXPORT vpRotationMatrix : public vpArray2D unsigned int m_index; }; -#ifndef DOXYGEN_SHOULD_SKIP_THIS -VISP_EXPORT -#endif -vpRotationMatrix operator*(const double &x, const vpRotationMatrix &R); #if defined(ENABLE_VISP_NAMESPACE) } #endif + +#ifndef DOXYGEN_SHOULD_SKIP_THIS +VISP_EXPORT +#endif +VISP_NAMESPACE_ADDRESSING vpRotationMatrix operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpRotationMatrix &R); #endif diff --git a/modules/core/include/visp3/core/vpRotationVector.h b/modules/core/include/visp3/core/vpRotationVector.h index 2adc11acec..aa6ba95a20 100644 --- a/modules/core/include/visp3/core/vpRotationVector.h +++ b/modules/core/include/visp3/core/vpRotationVector.h @@ -158,12 +158,13 @@ class VISP_EXPORT vpRotationVector : public vpArray2D unsigned int m_index; // index used for operator<< and operator, to fill a vector }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #ifndef DOXYGEN_SHOULD_SKIP_THIS VISP_EXPORT #endif -vpColVector operator*(const double &x, const vpRotationVector &v); +VISP_NAMESPACE_ADDRESSING vpColVector operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpRotationVector &v); -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif #endif diff --git a/modules/core/include/visp3/core/vpRowVector.h b/modules/core/include/visp3/core/vpRowVector.h index 880794827b..7a1b106eb5 100644 --- a/modules/core/include/visp3/core/vpRowVector.h +++ b/modules/core/include/visp3/core/vpRowVector.h @@ -340,8 +340,9 @@ class VISP_EXPORT vpRowVector : public vpArray2D #endif }; -VISP_EXPORT vpRowVector operator*(const double &x, const vpRowVector &v); #if defined(ENABLE_VISP_NAMESPACE) } #endif + +VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpRowVector operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpRowVector &v); #endif diff --git a/modules/core/src/camera/vpCameraParameters.cpp b/modules/core/src/camera/vpCameraParameters.cpp index af8f12ef4f..372c086c39 100644 --- a/modules/core/src/camera/vpCameraParameters.cpp +++ b/modules/core/src/camera/vpCameraParameters.cpp @@ -643,25 +643,14 @@ void vpCameraParameters::printParameters() std::cout.flags(original_flags); } -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - /*! * Print on the output stream \e os the camera parameters. * * \param os : Output stream. * \param cam : Camera parameters. */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const -#if defined(ENABLE_VISP_NAMESPACE) -visp:: -#endif -vpCameraParameters &cam) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpCameraParameters &cam) { -#if defined(ENABLE_VISP_NAMESPACE) - using namespace VISP_NAMESPACE_NAME; -#endif switch (cam.get_projModel()) { case vpCameraParameters::perspectiveProjWithoutDistortion: { os << "Camera parameters for perspective projection without distortion:" << std::endl; @@ -699,3 +688,6 @@ vpCameraParameters &cam) } return os; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/display/vpColor.cpp b/modules/core/src/display/vpColor.cpp index 7aa3b5ddc6..b3f135f7f8 100644 --- a/modules/core/src/display/vpColor.cpp +++ b/modules/core/src/display/vpColor.cpp @@ -124,10 +124,6 @@ vpColor const vpColor::allColors[vpColor::nbColors] = { vpColor::blue, // vpColor colors[6] = { vpColor::blue, vpColor::green, vpColor::red, vpColor::cyan, vpColor::orange, vpColor::purple }; -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - /*! Compare two colors. @@ -135,7 +131,7 @@ vpColor colors[6] = { vpColor::blue, vpColor::green, vpColor::red, vpColor::cyan \param c1,c2 : Color to compare. */ -VISP_EXPORT bool operator==(const VISP_NAMESPACE_ADDRESSING vpColor &c1, const VISP_NAMESPACE_ADDRESSING vpColor &c2) +VISP_EXPORT bool operator==(const vpColor &c1, const vpColor &c2) { return ((c1.R == c2.R) && (c1.G == c2.G) && (c1.B == c2.B)); } @@ -148,7 +144,11 @@ VISP_EXPORT bool operator==(const VISP_NAMESPACE_ADDRESSING vpColor &c1, const V \param c1,c2 : Color to compare. */ -VISP_EXPORT bool operator!=(const VISP_NAMESPACE_ADDRESSING vpColor &c1, const VISP_NAMESPACE_ADDRESSING vpColor &c2) +VISP_EXPORT bool operator!=(const vpColor &c1, const vpColor &c2) { return ((c1.R != c2.R) || (c1.G != c2.G) || (c1.B == c2.B)); } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/image/vpImagePoint.cpp b/modules/core/src/image/vpImagePoint.cpp index 76d1573c39..71d0f6304a 100644 --- a/modules/core/src/image/vpImagePoint.cpp +++ b/modules/core/src/image/vpImagePoint.cpp @@ -123,57 +123,13 @@ vpImagePoint &vpImagePoint::operator/=(double scale) return *this; } -/** - * Computes and returns the bounding box. - * @param ipVec : Vector of input image points. - * @return Bounding box of the points. - */ -vpRect vpImagePoint::getBBox(const std::vector &ipVec) -{ - vpRect rec(ipVec); - - return rec; -} - -/*! - Compute the distance \f$ |iP1 - iP2| = \sqrt{(i_1-i_2)^2+(j_1-j_2)^2} \f$ - - \param iP1 : First point - \param iP2 : Second point - - \return the distance between the two points. -*/ -double vpImagePoint::distance(const vpImagePoint &iP1, const vpImagePoint &iP2) -{ - return sqrt(vpMath::sqr(iP1.get_i() - iP2.get_i()) + vpMath::sqr(iP1.get_j() - iP2.get_j())); -} - -/*! - Compute the distance \f$ |iP1 - iP2| = (i_1-i_2)^2+(j_1-j_2)^2 \f$ - - \param iP1 : First point - \param iP2 : Second point - - \return the distance between the two points. -*/ -double vpImagePoint::sqrDistance(const vpImagePoint &iP1, const vpImagePoint &iP2) -{ - return vpMath::sqr(iP1.get_i() - iP2.get_i()) + vpMath::sqr(iP1.get_j() - iP2.get_j()); -} -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - /*! \relates vpImagePoint Returns true if ip1 and ip2 are equal; otherwire returns false. */ -VISP_EXPORT bool operator==(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip2) +VISP_EXPORT bool operator==(const vpImagePoint &ip1, const vpImagePoint &ip2) { -#ifdef ENABLE_VISP_NAMESPACE - using namespace VISP_NAMESPACE_NAME; -#endif // --comment: return ip1 dot get_i() eq ip2 dot get_i() and ip1 dot get_j() eq ip2 dot get_j() double i1 = ip1.get_i(); @@ -190,11 +146,8 @@ VISP_EXPORT bool operator==(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, c Returns true if ip1 and ip2 are different; otherwire returns true. */ -VISP_EXPORT bool operator!=(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip2) +VISP_EXPORT bool operator!=(const vpImagePoint &ip1, const vpImagePoint &ip2) { -#ifdef ENABLE_VISP_NAMESPACE - using namespace VISP_NAMESPACE_NAME; -#endif // --comment: return ip1 dot get_i() diff ip2 dot get_i() or ip1 dot get_j() diff ip2 dot get_j() double i1 = ip1.get_i(); double j1 = ip1.get_j(); @@ -210,9 +163,9 @@ VISP_EXPORT bool operator!=(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, c Returns a vpImagePoint wich is the sum of \f$ ip1 \f$ and \f$ ip2 \f$. */ -VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator+(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip2) +VISP_EXPORT vpImagePoint operator+(const vpImagePoint &ip1, const vpImagePoint &ip2) { - return (VISP_NAMESPACE_ADDRESSING vpImagePoint(ip1.get_i() + ip2.get_i(), ip1.get_j() + ip2.get_j())); + return (vpImagePoint(ip1.get_i() + ip2.get_i(), ip1.get_j() + ip2.get_j())); } /*! @@ -220,9 +173,9 @@ VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator+(const VISP_NAMESPAC Returns a vpImagePoint wich is the sum of \f$ ip1 \f$ and \f$ ip2 \f$. */ -VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator+=(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip2) +VISP_EXPORT vpImagePoint operator+=(const vpImagePoint &ip1, const vpImagePoint &ip2) { - return (VISP_NAMESPACE_ADDRESSING vpImagePoint(ip1.get_i() + ip2.get_i(), ip1.get_j() + ip2.get_j())); + return (vpImagePoint(ip1.get_i() + ip2.get_i(), ip1.get_j() + ip2.get_j())); } /*! @@ -244,9 +197,9 @@ int main() } \endcode */ -VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator+(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, int offset) +VISP_EXPORT vpImagePoint operator+(const vpImagePoint &ip1, int offset) { - return (VISP_NAMESPACE_ADDRESSING vpImagePoint(ip1.get_i() + offset, ip1.get_j() + offset)); + return (vpImagePoint(ip1.get_i() + offset, ip1.get_j() + offset)); } /*! @@ -268,9 +221,9 @@ int main() } \endcode */ -VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator+(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, unsigned int offset) +VISP_EXPORT vpImagePoint operator+(const vpImagePoint &ip1, unsigned int offset) { - return (VISP_NAMESPACE_ADDRESSING vpImagePoint(ip1.get_i() + offset, ip1.get_j() + offset)); + return (vpImagePoint(ip1.get_i() + offset, ip1.get_j() + offset)); } /*! @@ -292,9 +245,9 @@ int main() } \endcode */ -VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator+(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, double offset) +VISP_EXPORT vpImagePoint operator+(const vpImagePoint &ip1, double offset) { - return (VISP_NAMESPACE_ADDRESSING vpImagePoint(ip1.get_i() + offset, ip1.get_j() + offset)); + return (vpImagePoint(ip1.get_i() + offset, ip1.get_j() + offset)); } /*! @@ -303,9 +256,9 @@ VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator+(const VISP_NAMESPAC Returns a vpImagePoint wich is the difference between \f$ ip1 \f$ and \f$ ip2 \f$. */ -VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator-(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip2) +VISP_EXPORT vpImagePoint operator-(const vpImagePoint &ip1, const vpImagePoint &ip2) { - return (VISP_NAMESPACE_ADDRESSING vpImagePoint(ip1.get_i() - ip2.get_i(), ip1.get_j() - ip2.get_j())); + return (vpImagePoint(ip1.get_i() - ip2.get_i(), ip1.get_j() - ip2.get_j())); } /*! @@ -327,9 +280,9 @@ int main() } \endcode */ -VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator-(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, int offset) +VISP_EXPORT vpImagePoint operator-(const vpImagePoint &ip1, int offset) { - return (VISP_NAMESPACE_ADDRESSING vpImagePoint(ip1.get_i() - offset, ip1.get_j() - offset)); + return (vpImagePoint(ip1.get_i() - offset, ip1.get_j() - offset)); } /*! @@ -351,9 +304,9 @@ int main() } \endcode */ -VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator-(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, unsigned int offset) +VISP_EXPORT vpImagePoint operator-(const vpImagePoint &ip1, unsigned int offset) { - return (VISP_NAMESPACE_ADDRESSING vpImagePoint(ip1.get_i() - offset, ip1.get_j() - offset)); + return (vpImagePoint(ip1.get_i() - offset, ip1.get_j() - offset)); } /*! @@ -375,9 +328,9 @@ int main() } \endcode */ -VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator-(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, double offset) +VISP_EXPORT vpImagePoint operator-(const vpImagePoint &ip1, double offset) { - return (VISP_NAMESPACE_ADDRESSING vpImagePoint(ip1.get_i() - offset, ip1.get_j() - offset)); + return (vpImagePoint(ip1.get_i() - offset, ip1.get_j() - offset)); } /*! @@ -399,9 +352,9 @@ int main() } \endcode */ -VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator*(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, double scale) +VISP_EXPORT vpImagePoint operator*(const vpImagePoint &ip1, double scale) { - return (VISP_NAMESPACE_ADDRESSING vpImagePoint(ip1.get_i() * scale, ip1.get_j() * scale)); + return (vpImagePoint(ip1.get_i() * scale, ip1.get_j() * scale)); } /*! @@ -423,9 +376,9 @@ int main() } \endcode */ -VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpImagePoint operator/(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip1, double scale) +VISP_EXPORT vpImagePoint operator/(const vpImagePoint &ip1, double scale) { - return (VISP_NAMESPACE_ADDRESSING vpImagePoint(ip1.get_i() / scale, ip1.get_j() / scale)); + return (vpImagePoint(ip1.get_i() / scale, ip1.get_j() / scale)); } /*! @@ -459,8 +412,49 @@ int main() Image point with coordinates: 10, 11.1 \endverbatim */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpImagePoint &ip) { os << ip.get_i() << ", " << ip.get_j(); return os; } + +/** + * Computes and returns the bounding box. + * @param ipVec : Vector of input image points. + * @return Bounding box of the points. + */ +vpRect vpImagePoint::getBBox(const std::vector &ipVec) +{ + vpRect rec(ipVec); + + return rec; +} + +/*! + Compute the distance \f$ |iP1 - iP2| = \sqrt{(i_1-i_2)^2+(j_1-j_2)^2} \f$ + + \param iP1 : First point + \param iP2 : Second point + + \return the distance between the two points. +*/ +double vpImagePoint::distance(const vpImagePoint &iP1, const vpImagePoint &iP2) +{ + return sqrt(vpMath::sqr(iP1.get_i() - iP2.get_i()) + vpMath::sqr(iP1.get_j() - iP2.get_j())); +} + +/*! + Compute the distance \f$ |iP1 - iP2| = (i_1-i_2)^2+(j_1-j_2)^2 \f$ + + \param iP1 : First point + \param iP2 : Second point + + \return the distance between the two points. +*/ +double vpImagePoint::sqrDistance(const vpImagePoint &iP1, const vpImagePoint &iP2) +{ + return vpMath::sqr(iP1.get_i() - iP2.get_i()) + vpMath::sqr(iP1.get_j() - iP2.get_j()); +} +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/image/vpRGBa.cpp b/modules/core/src/image/vpRGBa.cpp index 5b4850e746..9cd2a22943 100644 --- a/modules/core/src/image/vpRGBa.cpp +++ b/modules/core/src/image/vpRGBa.cpp @@ -232,11 +232,8 @@ bool vpRGBa::operator>(const vpRGBa &v) const return (gray1 > gray2); } -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif -VISP_NAMESPACE_ADDRESSING vpRGBa operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpRGBa &rgb) { return rgb * x; } +VISP_NAMESPACE_ADDRESSING vpRGBa operator*(const double &x, const vpRGBa &rgb) { return rgb * x; } /*! @@ -260,8 +257,11 @@ int main() } \endcode */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpRGBa &rgba) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRGBa &rgba) { os << "(" << static_cast(rgba.R) << "," << static_cast(rgba.G) << "," << static_cast(rgba.B) << "," << static_cast(rgba.A) << ")"; return os; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/image/vpRGBf.cpp b/modules/core/src/image/vpRGBf.cpp index 748168277e..78e14c8e63 100644 --- a/modules/core/src/image/vpRGBf.cpp +++ b/modules/core/src/image/vpRGBf.cpp @@ -237,11 +237,8 @@ bool vpRGBf::operator>(const vpRGBf &v) const return (gray1 > gray2); } -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif -VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpRGBf operator*(double x, const VISP_NAMESPACE_ADDRESSING vpRGBf &rgb) { return rgb * x; } +VISP_EXPORT VISP_NAMESPACE_ADDRESSING vpRGBf operator*(double x, const vpRGBf &rgb) { return rgb * x; } /*! \relates vpRGBf @@ -264,8 +261,11 @@ int main() } \endcode */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpRGBf &rgb) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRGBf &rgb) { os << "(" << rgb.R << "," << rgb.G << "," << rgb.B << ")"; return os; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/matrix/vpColVector.cpp b/modules/core/src/math/matrix/vpColVector.cpp index f5e8363229..36dfcf6bfe 100644 --- a/modules/core/src/math/matrix/vpColVector.cpp +++ b/modules/core/src/math/matrix/vpColVector.cpp @@ -521,13 +521,6 @@ vpRowVector vpColVector::transpose() const { return t(); } void vpColVector::transpose(vpRowVector &v) const { v = t(); } -vpColVector operator*(const double &x, const vpColVector &v) -{ - vpColVector vout; - vout = v * x; - return vout; -} - double vpColVector::dotProd(const vpColVector &a, const vpColVector &b) { if (a.data == nullptr) { @@ -1019,3 +1012,10 @@ double vpColVector::euclideanNorm() const { return frobeniusNorm(); } #if defined(ENABLE_VISP_NAMESPACE) } #endif + +VISP_NAMESPACE_ADDRESSING vpColVector operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpColVector &v) +{ + VISP_NAMESPACE_ADDRESSING vpColVector vout; + vout = v * x; + return vout; +} diff --git a/modules/core/src/math/matrix/vpMatrix.cpp b/modules/core/src/math/matrix/vpMatrix.cpp index 056d2f6773..bcb406d2ea 100644 --- a/modules/core/src/math/matrix/vpMatrix.cpp +++ b/modules/core/src/math/matrix/vpMatrix.cpp @@ -1665,31 +1665,6 @@ double vpMatrix::sum() const // Matrix/real operations. //--------------------------------- -/*! - \relates vpMatrix - Allow to multiply a scalar by a matrix. -*/ -vpMatrix operator*(const double &x, const vpMatrix &B) -{ - if (std::fabs(x - 1.) < std::numeric_limits::epsilon()) { - return B; - } - - unsigned int Brow = B.getRows(); - unsigned int Bcol = B.getCols(); - - vpMatrix C; - C.resize(Brow, Bcol, false, false); - - for (unsigned int i = 0; i < Brow; ++i) { - for (unsigned int j = 0; j < Bcol; ++j) { - C[i][j] = B[i][j] * x; - } - } - - return C; -} - /*! Operator that allows to multiply all the elements of a matrix by a scalar. @@ -5025,35 +5000,35 @@ vpRowVector vpMatrix::getRow(unsigned int i) const { return getRow(i, 0, colNum) \param row_size : Size of the row vector to extract. \return The extracted row vector. - The following example shows how to use this function: - \code - #include - #include +The following example shows how to use this function: +\code +#include +#include - int main() - { - vpMatrix A(4,4); +int main() +{ + vpMatrix A(4, 4); - for(unsigned int i=0; i < A.getRows(); i++) - for(unsigned int j=0; j < A.getCols(); j++) - A[i][j] = i*A.getCols()+j; + for (unsigned int i = 0; i < A.getRows(); i++) + for (unsigned int j = 0; j < A.getCols(); j++) + A[i][j] = i*A.getCols()+j; - A.print(std::cout, 4); + A.print(std::cout, 4); - vpRowVector rv = A.getRow(1, 1, 3); - std::cout << "Row vector: \n" << rv << std::endl; - } - \endcode - It produces the following output : - \code - [4, 4] = - 0 1 2 3 - 4 5 6 7 - 8 9 10 11 - 12 13 14 15 - Row vector : - 5 6 7 - \endcode + vpRowVector rv = A.getRow(1, 1, 3); + std::cout << "Row vector: \n" << rv << std::endl; +} +\endcode +It produces the following output : +\code +[4, 4] = +0 1 2 3 +4 5 6 7 +8 9 10 11 +12 13 14 15 +Row vector : +5 6 7 +\endcode */ vpRowVector vpMatrix::getRow(unsigned int i, unsigned int j_begin, unsigned int row_size) const { @@ -6729,3 +6704,28 @@ void vpMatrix::setIdentity(const double &val) #if defined(ENABLE_VISP_NAMESPACE) } #endif + +/*! + \relates vpMatrix + Allow to multiply a scalar by a matrix. +*/ +VISP_NAMESPACE_ADDRESSING vpMatrix operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpMatrix &B) +{ + if (std::fabs(x - 1.) < std::numeric_limits::epsilon()) { + return B; + } + + unsigned int Brow = B.getRows(); + unsigned int Bcol = B.getCols(); + + VISP_NAMESPACE_ADDRESSING vpMatrix C; + C.resize(Brow, Bcol, false, false); + + for (unsigned int i = 0; i < Brow; ++i) { + for (unsigned int j = 0; j < Bcol; ++j) { + C[i][j] = B[i][j] * x; + } + } + + return C; +} diff --git a/modules/core/src/math/matrix/vpRowVector.cpp b/modules/core/src/math/matrix/vpRowVector.cpp index 6b5c2fd6cd..17b42ff7cb 100644 --- a/modules/core/src/math/matrix/vpRowVector.cpp +++ b/modules/core/src/math/matrix/vpRowVector.cpp @@ -1085,16 +1085,6 @@ int vpRowVector::print(std::ostream &s, unsigned int length, char const *intro) return static_cast(maxBefore + maxAfter); } -/*! - Allows to multiply a scalar by row vector. -*/ -vpRowVector operator*(const double &x, const vpRowVector &v) -{ - vpRowVector vout; - vout = v * x; - return vout; -} - /*! Return the sum of all the elements \f$v_{i}\f$ of the row vector v(n). @@ -1373,3 +1363,13 @@ std::ostream &vpRowVector::matlabPrint(std::ostream &os) const #if defined(ENABLE_VISP_NAMESPACE) } #endif + +/*! + Allows to multiply a scalar by row vector. +*/ +VISP_NAMESPACE_ADDRESSING vpRowVector operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpRowVector &v) +{ + VISP_NAMESPACE_ADDRESSING vpRowVector vout; + vout = v * x; + return vout; +} diff --git a/modules/core/src/math/transformation/vpRotationMatrix.cpp b/modules/core/src/math/transformation/vpRotationMatrix.cpp index f75cca57be..888fd7f3bb 100644 --- a/modules/core/src/math/transformation/vpRotationMatrix.cpp +++ b/modules/core/src/math/transformation/vpRotationMatrix.cpp @@ -948,25 +948,6 @@ vpRotationMatrix &vpRotationMatrix::build(const vpQuaternionVector &q) return *this; } -/*! - Allow to multiply a scalar by a rotation matrix. -*/ -vpRotationMatrix operator*(const double &x, const vpRotationMatrix &R) -{ - vpRotationMatrix C; - - unsigned int Rrow = R.getRows(); - unsigned int Rcol = R.getCols(); - - for (unsigned int i = 0; i < Rrow; ++i) { - for (unsigned int j = 0; j < Rcol; ++j) { - C[i][j] = R[i][j] * x; - } - } - - return C; -} - /*! Return the \f$\theta {\bf u}\f$ vector that corresponds to the rotation matrix. @@ -1145,3 +1126,22 @@ void vpRotationMatrix::setIdentity() { eye(); } #if defined(ENABLE_VISP_NAMESPACE) } #endif + +/*! + Allow to multiply a scalar by a rotation matrix. +*/ +VISP_NAMESPACE_ADDRESSING vpRotationMatrix operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpRotationMatrix &R) +{ + VISP_NAMESPACE_ADDRESSING vpRotationMatrix C; + + unsigned int Rrow = R.getRows(); + unsigned int Rcol = R.getCols(); + + for (unsigned int i = 0; i < Rrow; ++i) { + for (unsigned int j = 0; j < Rcol; ++j) { + C[i][j] = R[i][j] * x; + } + } + + return C; +} diff --git a/modules/core/src/math/transformation/vpRotationVector.cpp b/modules/core/src/math/transformation/vpRotationVector.cpp index 66c56f4d8f..9d8a171fb2 100644 --- a/modules/core/src/math/transformation/vpRotationVector.cpp +++ b/modules/core/src/math/transformation/vpRotationVector.cpp @@ -100,17 +100,6 @@ vpColVector vpRotationVector::operator*(double x) const return v; } -/*! - \relates vpRotationVector - Allows to multiply a scalar by rotaion vector. -*/ -vpColVector operator*(const double &x, const vpRotationVector &v) -{ - vpColVector vout; - vout = v * x; - return vout; -} - /*! Set vector first element value. \param val : Value of the vector first element [rad]. @@ -197,3 +186,14 @@ double vpRotationVector::sumSquare() const #if defined(ENABLE_VISP_NAMESPACE) } #endif + +/*! + \relates vpRotationVector + Allows to multiply a scalar by rotaion vector. +*/ +VISP_NAMESPACE_ADDRESSING vpColVector operator*(const double &x, const VISP_NAMESPACE_ADDRESSING vpRotationVector &v) +{ + VISP_NAMESPACE_ADDRESSING vpColVector vout; + vout = v * x; + return vout; +} diff --git a/modules/core/src/tools/exceptions/vpException.cpp b/modules/core/src/tools/exceptions/vpException.cpp index 6ef46fc632..36316d891b 100644 --- a/modules/core/src/tools/exceptions/vpException.cpp +++ b/modules/core/src/tools/exceptions/vpException.cpp @@ -72,13 +72,13 @@ const std::string &vpException::getStringMessage() const { return this->message; int vpException::getCode() const { return this->code; } const char *vpException::what() const throw() { return (this->message).c_str(); } -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpException &error) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpException &error) { os << "Error [" << error.code << "]:\t" << error.message << std::endl; return os; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tools/geometry/vpPlane.cpp b/modules/core/src/tools/geometry/vpPlane.cpp index 3a76de02f9..3042c5e858 100644 --- a/modules/core/src/tools/geometry/vpPlane.cpp +++ b/modules/core/src/tools/geometry/vpPlane.cpp @@ -383,17 +383,16 @@ void vpPlane::changeFrame(const vpHomogeneousMatrix &cMo) D = Do - ((cMo[0][3] * A) + (cMo[1][3] * B) + (cMo[2][3] * C)); } -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - /*! Print the plane parameters as a stream like "(A,B,C,D) " where A,B,C and D correspond to the parameters of the plane. */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpPlane &p) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpPlane &p) { return (os << "(" << p.getA() << "," << p.getB() << "," << p.getC() << "," << p.getD() << ") "); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tools/geometry/vpRect.cpp b/modules/core/src/tools/geometry/vpRect.cpp index c5ffec712c..2b29817a0a 100644 --- a/modules/core/src/tools/geometry/vpRect.cpp +++ b/modules/core/src/tools/geometry/vpRect.cpp @@ -255,9 +255,6 @@ bool vpRect::operator!=(const vpRect &r) const */ return !(*this == r); } -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif /*! Check if an image point belongs to a rectangle. @@ -267,14 +264,17 @@ bool vpRect::operator!=(const vpRect &r) const \return Returns true if the point belongs to the rectangle. */ -VISP_EXPORT bool inRectangle(const VISP_NAMESPACE_ADDRESSING vpImagePoint &ip, const VISP_NAMESPACE_ADDRESSING vpRect &rect) +VISP_EXPORT bool inRectangle(const vpImagePoint &ip, const vpRect &rect) { return ((ip.get_i() <= rect.getBottom()) && (ip.get_i() >= rect.getTop()) && (ip.get_j() <= rect.getRight()) && (ip.get_j() >= rect.getLeft())); } -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpRect &r) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpRect &r) { os << r.getLeft() << ", " << r.getTop() << ", " << r.getWidth() << ", " << r.getHeight(); return os; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tools/histogram/vpHistogramPeak.cpp b/modules/core/src/tools/histogram/vpHistogramPeak.cpp index cb8416900e..ff5ab33bc4 100644 --- a/modules/core/src/tools/histogram/vpHistogramPeak.cpp +++ b/modules/core/src/tools/histogram/vpHistogramPeak.cpp @@ -88,21 +88,21 @@ vpHistogramPeak &vpHistogramPeak::operator=(const vpHistogramPeak &p) */ bool vpHistogramPeak::operator==(const vpHistogramPeak &p) const { return ((level == p.level) && (value == p.value)); } -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif /*! \relates vpHistogramPeak \brief std::cout a peak */ -VISP_EXPORT std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING vpHistogramPeak &p) +VISP_EXPORT std::ostream &operator<<(std::ostream &s, const vpHistogramPeak &p) { s << static_cast(p.getLevel()) << " " << p.getValue(); return s; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif /* * Local variables: * c-basic-offset: 2 diff --git a/modules/core/src/tools/histogram/vpHistogramValey.cpp b/modules/core/src/tools/histogram/vpHistogramValey.cpp index 25d8458ef2..9391e21ae4 100644 --- a/modules/core/src/tools/histogram/vpHistogramValey.cpp +++ b/modules/core/src/tools/histogram/vpHistogramValey.cpp @@ -77,15 +77,11 @@ bool vpHistogramValey::operator==(const vpHistogramValey &v) const return ((level == v.level) && (value == v.value)); } -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - /*! \relates vpHistogramValey \brief std::cout a valey */ -VISP_EXPORT std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRESSING vpHistogramValey &v) +VISP_EXPORT std::ostream &operator<<(std::ostream &s, const vpHistogramValey &v) { s << static_cast(v.getLevel()) << " " << v.getValue(); @@ -93,6 +89,9 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &s, const VISP_NAMESPACE_ADDRE return s; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif /* * Local variables: * c-basic-offset: 2 diff --git a/modules/core/src/tracking/forward-projection/vpPoint.cpp b/modules/core/src/tracking/forward-projection/vpPoint.cpp index f07a3054c7..c2a7e786c3 100644 --- a/modules/core/src/tracking/forward-projection/vpPoint.cpp +++ b/modules/core/src/tracking/forward-projection/vpPoint.cpp @@ -508,8 +508,8 @@ void vpPoint::set_x(double x) { p[0] = x; } void vpPoint::set_y(double y) { p[1] = y; } //! Set the point w coordinate in the image plane. void vpPoint::set_w(double w) { p[2] = w; } + +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpPoint & /* vpp */) { return (os << "vpPoint"); } #if defined(ENABLE_VISP_NAMESPACE) } #endif - -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpPoint & /* vpp */) { return (os << "vpPoint"); } diff --git a/modules/core/src/tracking/moments/vpMoment.cpp b/modules/core/src/tracking/moments/vpMoment.cpp index 1da05131eb..ac29937392 100644 --- a/modules/core/src/tracking/moments/vpMoment.cpp +++ b/modules/core/src/tracking/moments/vpMoment.cpp @@ -41,12 +41,16 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace VISP_NAMESPACE_NAME +{ +#endif /*! * Prints the moment contents to a stream * \param os : a std::stream. * \param m : a moment instance. */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMoment &m) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMoment &m) { for (std::vector::const_iterator i = m.values.begin(); i != m.values.end(); ++i) os << *i << ","; @@ -54,10 +58,6 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDR return os; } -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * Default constructor */ diff --git a/modules/core/src/tracking/moments/vpMomentAlpha.cpp b/modules/core/src/tracking/moments/vpMomentAlpha.cpp index 3cf523ca56..d01dd8ed74 100644 --- a/modules/core/src/tracking/moments/vpMomentAlpha.cpp +++ b/modules/core/src/tracking/moments/vpMomentAlpha.cpp @@ -177,14 +177,10 @@ void vpMomentAlpha::printDependencies(std::ostream &os) const os << "mu02 = " << momentCentered.get(0, 2) << std::endl; } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - /*! Prints the value of the major-axis orientation in degrees and rad */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentAlpha &c) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentAlpha &c) { #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME; @@ -193,3 +189,7 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDR os << "Alpha = " << c.values[0] << "rad = " << vpMath::deg(c.values[0]) << "deg " << std::endl; return os; } + +#ifdef ENABLE_VISP_NAMESPACE +} +#endif diff --git a/modules/core/src/tracking/moments/vpMomentArea.cpp b/modules/core/src/tracking/moments/vpMomentArea.cpp index da0f65df79..1f6adb83c8 100644 --- a/modules/core/src/tracking/moments/vpMomentArea.cpp +++ b/modules/core/src/tracking/moments/vpMomentArea.cpp @@ -100,16 +100,17 @@ void vpMomentArea::printDependencies(std::ostream &os) const os << "mu00 = " << momentCentered.get(0, 0) << std::endl; } } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif /*! Outputs the moment's values to a stream. */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentArea &m) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentArea &m) { os << (__FILE__) << std::endl; os << "a(m00) = " << m.values[0] << std::endl; return os; } + +#ifdef ENABLE_VISP_NAMESPACE +} +#endif diff --git a/modules/core/src/tracking/moments/vpMomentAreaNormalized.cpp b/modules/core/src/tracking/moments/vpMomentAreaNormalized.cpp index 841f65b0d9..511d8a8790 100644 --- a/modules/core/src/tracking/moments/vpMomentAreaNormalized.cpp +++ b/modules/core/src/tracking/moments/vpMomentAreaNormalized.cpp @@ -114,17 +114,16 @@ void vpMomentAreaNormalized::printDependencies(std::ostream &os) const a = getObject().get(0, 0); os << "a = " << a << std::endl; } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - /*! Outputs the moment's values to a stream. */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentAreaNormalized &m) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentAreaNormalized &m) { os << (__FILE__) << std::endl; os << "An = " << m.values[0] << std::endl; return os; } +#ifdef ENABLE_VISP_NAMESPACE +} +#endif diff --git a/modules/core/src/tracking/moments/vpMomentBasic.cpp b/modules/core/src/tracking/moments/vpMomentBasic.cpp index 8dbbd6269b..a0a9ccf6a3 100644 --- a/modules/core/src/tracking/moments/vpMomentBasic.cpp +++ b/modules/core/src/tracking/moments/vpMomentBasic.cpp @@ -83,20 +83,17 @@ void vpMomentBasic::printDependencies(std::ostream &os) const << std::endl; vpMomentObject::printWithIndices(getObject(), os); } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif /*! Outputs the moment's values to a stream. Same output as in vpMomentObject. */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentBasic &m) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentBasic &m) { -#ifdef ENABLE_VISP_NAMESPACE - using namespace VISP_NAMESPACE_NAME; -#endif os << (__FILE__) << std::endl; vpMomentObject::printWithIndices(m.getObject(), os); return os; } +#ifdef ENABLE_VISP_NAMESPACE +} +#endif diff --git a/modules/core/src/tracking/moments/vpMomentCInvariant.cpp b/modules/core/src/tracking/moments/vpMomentCInvariant.cpp index b8f663590d..ea9891d3c7 100644 --- a/modules/core/src/tracking/moments/vpMomentCInvariant.cpp +++ b/modules/core/src/tracking/moments/vpMomentCInvariant.cpp @@ -285,17 +285,17 @@ void vpMomentCInvariant::printInvariants(std::ostream &os) const } os << std::endl; } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif /*! Outputs the moment's values to a stream. */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentCInvariant &c) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentCInvariant &c) { for (unsigned int i = 0; i < c.values.size(); i++) { os << c.values[i] << "," << std::endl; } return os; } +#ifdef ENABLE_VISP_NAMESPACE +} +#endif diff --git a/modules/core/src/tracking/moments/vpMomentCentered.cpp b/modules/core/src/tracking/moments/vpMomentCentered.cpp index eb9da481b7..c28943e999 100644 --- a/modules/core/src/tracking/moments/vpMomentCentered.cpp +++ b/modules/core/src/tracking/moments/vpMomentCentered.cpp @@ -157,9 +157,6 @@ void vpMomentCentered::printDependencies(std::ostream &os) const os << "Xg = " << momentGravity.getXg() << "\t" << "Yg = " << momentGravity.getYg() << std::endl; } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif /*! Outputs the centered moment's values \f$\mu_{ij}\f$ to a stream presented as @@ -179,7 +176,7 @@ u30 x x x This output will be followed by an output with indexes as produced by printWithIndices() function */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentCentered &m) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentCentered &m) { for (unsigned int i = 0; i < m.values.size(); i++) { if (i % (m.getObject().getOrder() + 1) == 0) @@ -196,3 +193,6 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDR m.printWithIndices(os); return os; } +#ifdef ENABLE_VISP_NAMESPACE +} +#endif diff --git a/modules/core/src/tracking/moments/vpMomentDatabase.cpp b/modules/core/src/tracking/moments/vpMomentDatabase.cpp index 12642ec3c3..4c4ffca129 100644 --- a/modules/core/src/tracking/moments/vpMomentDatabase.cpp +++ b/modules/core/src/tracking/moments/vpMomentDatabase.cpp @@ -90,14 +90,11 @@ void vpMomentDatabase::updateAll(vpMomentObject &object) (*itr).second->update(object); } } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif /*! * Outputs all the moments values in the database to a stream. */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentDatabase &m) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentDatabase &m) { #ifdef ENABLE_VISP_NAMESPACE using namespace VISP_NAMESPACE_NAME; @@ -112,3 +109,6 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDR return os; } +#ifdef ENABLE_VISP_NAMESPACE +} +#endif diff --git a/modules/core/src/tracking/moments/vpMomentGravityCenter.cpp b/modules/core/src/tracking/moments/vpMomentGravityCenter.cpp index 1a79e04218..6d7105f50e 100644 --- a/modules/core/src/tracking/moments/vpMomentGravityCenter.cpp +++ b/modules/core/src/tracking/moments/vpMomentGravityCenter.cpp @@ -75,16 +75,16 @@ void vpMomentGravityCenter::printDependencies(std::ostream &os) const os << "m00 = " << getObject().get(0, 1) << "\t"; os << "m00 = " << getObject().get(0, 0) << std::endl; } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif /*! Outputs the moment's values to a stream. */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentGravityCenter &m) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentGravityCenter &m) { os << (__FILE__) << std::endl; os << "(Xg,Yg) = (" << m.values[0] << ", " << m.values[1] << ")" << std::endl; return os; } +#ifdef ENABLE_VISP_NAMESPACE +} +#endif diff --git a/modules/core/src/tracking/moments/vpMomentGravityCenterNormalized.cpp b/modules/core/src/tracking/moments/vpMomentGravityCenterNormalized.cpp index 8476cc5bf7..93bead2439 100644 --- a/modules/core/src/tracking/moments/vpMomentGravityCenterNormalized.cpp +++ b/modules/core/src/tracking/moments/vpMomentGravityCenterNormalized.cpp @@ -101,16 +101,16 @@ void vpMomentGravityCenterNormalized::printDependencies(std::ostream &os) const << "Yg = " << momentGravity.get()[1] << std::endl; os << "An = " << momentSurfaceNormalized.get()[0] << std::endl; } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif /*! Outputs the moment's values to a stream. */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentGravityCenterNormalized &m) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentGravityCenterNormalized &m) { os << (__FILE__) << std::endl; os << "(Xn,Yn) = (" << m.values[0] << ", " << m.values[1] << ")" << std::endl; return os; } +#ifdef ENABLE_VISP_NAMESPACE +} +#endif diff --git a/modules/core/src/tracking/moments/vpMomentObject.cpp b/modules/core/src/tracking/moments/vpMomentObject.cpp index f092d76f55..8c679bf217 100644 --- a/modules/core/src/tracking/moments/vpMomentObject.cpp +++ b/modules/core/src/tracking/moments/vpMomentObject.cpp @@ -635,9 +635,6 @@ vpMomentObject::~vpMomentObject() { // deliberate empty } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif /*! Outputs the basic moment's values \f$m_{ij}\f$ to a stream presented as a @@ -654,7 +651,7 @@ vpMomentObject::~vpMomentObject() m03 x x x \endcode */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpMomentObject &m) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpMomentObject &m) { for (unsigned int i = 0; i < m.values.size(); ++i) { @@ -673,3 +670,6 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDR return os; } +#ifdef ENABLE_VISP_NAMESPACE +} +#endif diff --git a/modules/imgproc/include/visp3/imgproc/vpContours.h b/modules/imgproc/include/visp3/imgproc/vpContours.h index 743ff1952b..7252feb2fd 100644 --- a/modules/imgproc/include/visp3/imgproc/vpContours.h +++ b/modules/imgproc/include/visp3/imgproc/vpContours.h @@ -77,7 +77,7 @@ #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) namespace vp #else -namespace visp +namespace VISP_NAMESPACE_NAME #endif { diff --git a/modules/imgproc/include/visp3/imgproc/vpImgproc.h b/modules/imgproc/include/visp3/imgproc/vpImgproc.h index a2c315ac5f..677d8a925f 100644 --- a/modules/imgproc/include/visp3/imgproc/vpImgproc.h +++ b/modules/imgproc/include/visp3/imgproc/vpImgproc.h @@ -48,7 +48,7 @@ #ifdef VISP_BUILD_DEPRECATED_FUNCTIONS #define VISP_IMGPROC_NAMESPACE vp #else -#define VISP_IMGPROC_NAMESPACE visp +#define VISP_IMGPROC_NAMESPACE VISP_NAMESPACE_NAME #endif namespace VISP_IMGPROC_NAMESPACE diff --git a/modules/imgproc/src/vpCLAHE.cpp b/modules/imgproc/src/vpCLAHE.cpp index 38ff57d97a..88ed860bb0 100644 --- a/modules/imgproc/src/vpCLAHE.cpp +++ b/modules/imgproc/src/vpCLAHE.cpp @@ -82,7 +82,7 @@ #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) namespace vp #else -namespace visp +namespace VISP_NAMESPACE_NAME #endif { diff --git a/modules/imgproc/src/vpConnectedComponents.cpp b/modules/imgproc/src/vpConnectedComponents.cpp index aa0adb3f3b..00f98acff8 100644 --- a/modules/imgproc/src/vpConnectedComponents.cpp +++ b/modules/imgproc/src/vpConnectedComponents.cpp @@ -42,7 +42,7 @@ #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) namespace vp #else -namespace visp +namespace VISP_NAMESPACE_NAME #endif { diff --git a/modules/imgproc/src/vpContours.cpp b/modules/imgproc/src/vpContours.cpp index 0a195f0208..c67aa67516 100644 --- a/modules/imgproc/src/vpContours.cpp +++ b/modules/imgproc/src/vpContours.cpp @@ -73,7 +73,7 @@ #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) namespace vp #else -namespace visp +namespace VISP_NAMESPACE_NAME #endif { diff --git a/modules/imgproc/src/vpFloodFill.cpp b/modules/imgproc/src/vpFloodFill.cpp index 368b8e2a88..3bfca2b9ce 100644 --- a/modules/imgproc/src/vpFloodFill.cpp +++ b/modules/imgproc/src/vpFloodFill.cpp @@ -69,7 +69,7 @@ #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) namespace vp #else -namespace visp +namespace VISP_NAMESPACE_NAME #endif { diff --git a/modules/imgproc/src/vpMorph.cpp b/modules/imgproc/src/vpMorph.cpp index d252708a96..f6b652819f 100644 --- a/modules/imgproc/src/vpMorph.cpp +++ b/modules/imgproc/src/vpMorph.cpp @@ -42,7 +42,7 @@ #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) namespace vp #else -namespace visp +namespace VISP_NAMESPACE_NAME #endif { diff --git a/modules/imgproc/src/vpRetinex.cpp b/modules/imgproc/src/vpRetinex.cpp index c26661efdb..248d9260ed 100644 --- a/modules/imgproc/src/vpRetinex.cpp +++ b/modules/imgproc/src/vpRetinex.cpp @@ -91,7 +91,7 @@ #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) namespace vp #else -namespace visp +namespace VISP_NAMESPACE_NAME #endif { diff --git a/modules/imgproc/src/vpThreshold.cpp b/modules/imgproc/src/vpThreshold.cpp index 97351741b8..9b9d531adc 100644 --- a/modules/imgproc/src/vpThreshold.cpp +++ b/modules/imgproc/src/vpThreshold.cpp @@ -43,7 +43,7 @@ #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) namespace vp #else -namespace visp +namespace VISP_NAMESPACE_NAME #endif { diff --git a/modules/imgproc/test/with-dataset/testAutoThreshold.cpp b/modules/imgproc/test/with-dataset/testAutoThreshold.cpp index 2de7a84f55..79e9ae70f9 100644 --- a/modules/imgproc/test/with-dataset/testAutoThreshold.cpp +++ b/modules/imgproc/test/with-dataset/testAutoThreshold.cpp @@ -31,21 +31,25 @@ * Test automatic thresholding. */ -#include -#include -#include -#include -#include - /*! \example testAutoThreshold.cpp \brief Test automatic thresholding. */ +#include +#include +#include +#include +#include + // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string opath, std::string user); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &opath, std::string user); @@ -61,9 +65,9 @@ bool getOptions(int argc, const char **argv, std::string &ipath, std::string &op void usage(const char *name, const char *badparam, std::string ipath, std::string opath, std::string user) { #if VISP_HAVE_DATASET_VERSION >= 0x030600 - std::string ext("png"); + std::string ext("png"); #else - std::string ext("pgm"); + std::string ext("pgm"); #endif fprintf(stdout, "\n\ Test automatic thresholding.\n\ @@ -72,7 +76,7 @@ SYNOPSIS\n\ %s [-i ] [-o ]\n\ [-h]\n \ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -203,7 +207,8 @@ int main(int argc, const char **argv) try { // Create the dirname vpIoTools::makeDirectory(opath); - } catch (...) { + } + catch (...) { usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; @@ -218,8 +223,8 @@ int main(int argc, const char **argv) if (ipath != env_ipath) { std::cout << std::endl << "WARNING: " << std::endl; std::cout << " Since -i " - << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl - << " we skip the environment variable." << std::endl; + << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl + << " we skip the environment variable." << std::endl; } } @@ -228,9 +233,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl - << " environment variable to specify the location of the " << std::endl - << " image path where test images are located." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << std::endl; exit(EXIT_FAILURE); } @@ -311,7 +316,8 @@ int main(int argc, const char **argv) std::cout << "Write: " << filename << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/imgproc/test/with-dataset/testConnectedComponents.cpp b/modules/imgproc/test/with-dataset/testConnectedComponents.cpp index de888663c9..8b8b8fe2dd 100644 --- a/modules/imgproc/test/with-dataset/testConnectedComponents.cpp +++ b/modules/imgproc/test/with-dataset/testConnectedComponents.cpp @@ -30,6 +30,13 @@ * Description: * Test connected components. */ + +/*! + \example testConnectedComponents.cpp + + \brief Test connected components. +*/ + #include #include #include @@ -38,15 +45,13 @@ #include #include -/*! - \example testConnectedComponents.cpp - - \brief Test connected components. -*/ - // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string opath, std::string user); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &opath, std::string user); bool checkLabels(const vpImage &label1, const vpImage &label2); @@ -69,7 +74,7 @@ SYNOPSIS\n\ %s [-i ] [-o ]\n\ [-h]\n \ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -156,8 +161,8 @@ bool checkLabels(const vpImage &label1, const vpImage &label2) for (unsigned int j = 0; j < label1.getWidth(); j++) { if ((label1[i][j] > 0 && label2[i][j] == 0) || (label1[i][j] == 0 && label2[i][j] > 0)) { std::cerr << "label1[i][j] > 0 && label2[i][j] == 0 || label1[i][j] " - "== 0 && label2[i][j] > 0" - << std::endl; + "== 0 && label2[i][j] > 0" + << std::endl; return false; } @@ -242,7 +247,8 @@ int main(int argc, const char **argv) try { // Create the dirname vpIoTools::makeDirectory(opath); - } catch (...) { + } + catch (...) { usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; @@ -257,8 +263,8 @@ int main(int argc, const char **argv) if (ipath != env_ipath) { std::cout << std::endl << "WARNING: " << std::endl; std::cout << " Since -i " - << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl - << " we skip the environment variable." << std::endl; + << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl + << " we skip the environment variable." << std::endl; } } @@ -267,9 +273,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl - << " environment variable to specify the location of the " << std::endl - << " image path where test images are located." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << std::endl; exit(EXIT_FAILURE); } @@ -393,7 +399,8 @@ int main(int argc, const char **argv) #endif return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/imgproc/test/with-dataset/testContours.cpp b/modules/imgproc/test/with-dataset/testContours.cpp index b1c7a9b9a3..60f263c317 100644 --- a/modules/imgproc/test/with-dataset/testContours.cpp +++ b/modules/imgproc/test/with-dataset/testContours.cpp @@ -31,6 +31,12 @@ * Test contours extraction. */ +/*! + \example testContours.cpp + + \brief Test contours extraction. +*/ + #include #include @@ -39,15 +45,13 @@ #include #include -/*! - \example testContours.cpp - - \brief Test contours extraction. -*/ - // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string opath, std::string user); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &opath, std::string user); @@ -69,7 +73,7 @@ SYNOPSIS\n\ %s [-i ] [-o ]\n\ [-h]\n \ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -172,7 +176,7 @@ void displayContourInfo(const vp::vpContour &contour, int level) std::cout << "\nContour:" << std::endl; std::cout << "\tlevel: " << level << std::endl; std::cout << "\tcontour type: " << (contour.m_contourType == vp::CONTOUR_OUTER ? "outer contour" : "hole contour") - << std::endl; + << std::endl; std::cout << "\tnb children: " << contour.m_children.size() << std::endl; for (std::vector::const_iterator it = contour.m_children.begin(); it != contour.m_children.end(); @@ -229,7 +233,8 @@ int main(int argc, const char **argv) try { // Create the dirname vpIoTools::makeDirectory(opath); - } catch (...) { + } + catch (...) { usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; @@ -244,8 +249,8 @@ int main(int argc, const char **argv) if (ipath != env_ipath) { std::cout << std::endl << "WARNING: " << std::endl; std::cout << " Since -i " - << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl - << " we skip the environment variable." << std::endl; + << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl + << " we skip the environment variable." << std::endl; } } @@ -254,9 +259,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl - << " environment variable to specify the location of the " << std::endl - << " image path where test images are located." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << std::endl; exit(EXIT_FAILURE); } @@ -268,7 +273,7 @@ int main(int argc, const char **argv) 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 0, 0, 1, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 0, 0, 0, 0, 1, 0, 0, 1, 0, 0, 1, 0, 0, 0, 1, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 1, 0, 0, - 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 1, 0, 1, 0, 0, 0, 0, 0, 1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; + 0, 1, 0, 0, 0, 0, 0, 1, 0, 1, 1, 0, 1, 0, 0, 0, 0, 0, 1, 0, 0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; vpImage I_test_data(image_data, 14, 10, true); std::cout << "Test with image data:" << std::endl; @@ -353,7 +358,7 @@ int main(int argc, const char **argv) vp::drawContours(I_draw_contours_external, contours); std::cout << "(I_tmp_external == I_draw_contours_external)? " << (I_tmp_external == I_draw_contours_external) - << std::endl; + << std::endl; filename = vpIoTools::createFilePath(opath, "Klimt_contours_extracted_external.pgm"); vpImageIo::write(I_draw_contours_external, filename); @@ -390,7 +395,7 @@ int main(int argc, const char **argv) } std::cout << "(I_draw_contours_opencv == I_drawContours)? " << (I_draw_contours_opencv == I_draw_contours) - << std::endl; + << std::endl; filename = vpIoTools::createFilePath(opath, "Klimt_contours_extracted_opencv.pgm"); vpImageIo::write(I_draw_contours_opencv, filename); @@ -409,9 +414,9 @@ int main(int argc, const char **argv) } std::cout << "(I_draw_contours_opencv == I_draw_contours_list)? " - << (I_draw_contours_opencv == I_draw_contours_list) << std::endl; + << (I_draw_contours_opencv == I_draw_contours_list) << std::endl; - // Test retrieve external +// Test retrieve external vpImageConvert::convert(I, matImg); contours_opencv.clear(); cv::findContours(matImg, contours_opencv, cv::RETR_EXTERNAL, cv::CHAIN_APPROX_NONE); @@ -425,11 +430,12 @@ int main(int argc, const char **argv) } std::cout << "(I_draw_contours_opencv == I_draw_contours_external)? " - << (I_draw_contours_opencv == I_draw_contours_external) << std::endl; + << (I_draw_contours_opencv == I_draw_contours_external) << std::endl; #endif return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } diff --git a/modules/imgproc/test/with-dataset/testFloodFill.cpp b/modules/imgproc/test/with-dataset/testFloodFill.cpp index dfe48dcd43..ba3a449f5f 100644 --- a/modules/imgproc/test/with-dataset/testFloodFill.cpp +++ b/modules/imgproc/test/with-dataset/testFloodFill.cpp @@ -31,6 +31,12 @@ * Test flood fill algorithm. */ +/*! + \example testFloodFill.cpp + + \brief Test flood fill algorithm. +*/ + #include #include @@ -39,15 +45,13 @@ #include #include -/*! - \example testFloodFill.cpp - - \brief Test flood fill algorithm. -*/ - // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string opath, std::string user); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &opath, std::string user); @@ -69,7 +73,7 @@ SYNOPSIS\n\ %s [-i ] [-o ]\n\ [-h]\n \ ", - name); +name); fprintf(stdout, "\n\ OPTIONS: Default\n\ @@ -221,7 +225,8 @@ int main(int argc, const char **argv) try { // Create the dirname vpIoTools::makeDirectory(opath); - } catch (...) { + } + catch (...) { usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Cannot create " << opath << std::endl; @@ -236,8 +241,8 @@ int main(int argc, const char **argv) if (ipath != env_ipath) { std::cout << std::endl << "WARNING: " << std::endl; std::cout << " Since -i " - << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl - << " we skip the environment variable." << std::endl; + << " is different from VISP_IMAGE_PATH=" << env_ipath << std::endl + << " we skip the environment variable." << std::endl; } } @@ -246,9 +251,9 @@ int main(int argc, const char **argv) usage(argv[0], nullptr, ipath, opt_opath, username); std::cerr << std::endl << "ERROR:" << std::endl; std::cerr << " Use -i option or set VISP_INPUT_IMAGE_PATH " << std::endl - << " environment variable to specify the location of the " << std::endl - << " image path where test images are located." << std::endl - << std::endl; + << " environment variable to specify the location of the " << std::endl + << " image path where test images are located." << std::endl + << std::endl; exit(EXIT_FAILURE); } @@ -256,21 +261,21 @@ int main(int argc, const char **argv) // Here starts really the test // - unsigned char image_data[8 * 8] = {1, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 0, 0, 0, 1, 0, 0, 0, 1, 0, + unsigned char image_data[8 * 8] = { 1, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 0, 0, 0, 1, 0, 0, 0, 1, 0, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0, 1, 1, 1, 1, 0, 1, 1, 1, 1, 0, 0, 1, - 1, 0, 1, 0, 1, 0, 0, 0, 1, 0, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0}; + 1, 0, 1, 0, 1, 0, 0, 0, 1, 0, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0 }; vpImage I_test_flood_fill_4_connexity(image_data, 8, 8, true); vpImage I_test_flood_fill_8_connexity = I_test_flood_fill_4_connexity; printImage(I_test_flood_fill_4_connexity, "Test image data"); unsigned char image_data_check_4_connexity[8 * 8] = { 1, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 0, 0, 0, 1, 1, 1, 1, 1, 0, 1, 0, 1, 1, 1, 1, 1, 1, 1, 0, - 1, 1, 1, 1, 0, 1, 1, 1, 1, 0, 0, 1, 1, 0, 1, 0, 1, 0, 0, 0, 1, 0, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0}; + 1, 1, 1, 1, 0, 1, 1, 1, 1, 0, 0, 1, 1, 0, 1, 0, 1, 0, 0, 0, 1, 0, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0 }; vpImage I_check_4_connexity(image_data_check_4_connexity, 8, 8, true); unsigned char image_data_check_8_connexity[8 * 8] = { 1, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 0, 0, 0, 1, 1, 1, 1, 1, 0, 1, 0, 1, 1, 1, 1, 1, 1, 1, 0, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 1, 1, 1, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0}; + 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 1, 1, 1, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0, 1, 0, 0, 0, 1, 1, 1, 0 }; vpImage I_check_8_connexity(image_data_check_8_connexity, 8, 8, true); // Test flood fill on test data 4-connexity @@ -281,9 +286,9 @@ int main(int argc, const char **argv) throw vpException(vpException::fatalError, "Problem with vp::floodFill() and 4-connexity!"); } std::cout << "\n(I_test_flood_fill_4_connexity == I_check_4_connexity)? " - << (I_test_flood_fill_4_connexity == I_check_4_connexity) << std::endl; + << (I_test_flood_fill_4_connexity == I_check_4_connexity) << std::endl; - // Test flood fill on test data 8-connexity +// Test flood fill on test data 8-connexity vp::floodFill(I_test_flood_fill_8_connexity, vpImagePoint(2, 2), 0, 1, vpImageMorphology::CONNEXITY_8); printImage(I_test_flood_fill_8_connexity, "I_test_flood_fill_8_connexity"); @@ -291,15 +296,15 @@ int main(int argc, const char **argv) throw vpException(vpException::fatalError, "Problem with vp::floodFill() and 8-connexity!"); } std::cout << "\n(I_test_flood_fill_8_connexity == I_check_8_connexity)? " - << (I_test_flood_fill_8_connexity == I_check_8_connexity) << std::endl; + << (I_test_flood_fill_8_connexity == I_check_8_connexity) << std::endl; - // Read Klimt.ppm +// Read Klimt.ppm filename = vpIoTools::createFilePath(ipath, "Klimt/Klimt.pgm"); vpImage I_klimt; vpImageIo::read(I_klimt, filename); std::cout << "\nRead image: " << filename << " (" << I_klimt.getWidth() << "x" << I_klimt.getHeight() << ")" - << std::endl - << std::endl; + << std::endl + << std::endl; vpImageTools::binarise(I_klimt, (unsigned char)127, (unsigned char)255, (unsigned char)0, (unsigned char)255, (unsigned char)255); @@ -355,11 +360,11 @@ int main(int argc, const char **argv) // Check std::cout << "\n(I_klimt_flood_fill_4_connexity == " - "I_klimt_flood_fill_4_connexity_check)? " - << (I_klimt_flood_fill_4_connexity == I_klimt_flood_fill_4_connexity_check) << std::endl; + "I_klimt_flood_fill_4_connexity_check)? " + << (I_klimt_flood_fill_4_connexity == I_klimt_flood_fill_4_connexity_check) << std::endl; std::cout << "(I_klimt_flood_fill_8_connexity == " - "I_klimt_flood_fill_8_connexity_check)? " - << (I_klimt_flood_fill_8_connexity == I_klimt_flood_fill_8_connexity_check) << std::endl; + "I_klimt_flood_fill_8_connexity_check)? " + << (I_klimt_flood_fill_8_connexity == I_klimt_flood_fill_8_connexity_check) << std::endl; if (I_klimt_flood_fill_4_connexity != I_klimt_flood_fill_4_connexity_check) { throw vpException(vpException::fatalError, "(I_klimt_flood_fill_4_connexity != " @@ -372,13 +377,14 @@ int main(int argc, const char **argv) std::cout << "\nTest flood fill is ok!" << std::endl; return EXIT_SUCCESS; - } catch (const vpException &e) { + } + catch (const vpException &e) { std::cerr << "Catch an exception: " << e.what() << std::endl; return EXIT_FAILURE; } #else - (void) argc; - (void) argv; + (void)argc; + (void)argv; std::cout << "Install OpenCV imgproc module required by this test" << std::endl; return EXIT_SUCCESS; #endif diff --git a/modules/imgproc/test/with-dataset/testImgproc.cpp b/modules/imgproc/test/with-dataset/testImgproc.cpp index 3f2fb03636..9e94047d9c 100644 --- a/modules/imgproc/test/with-dataset/testImgproc.cpp +++ b/modules/imgproc/test/with-dataset/testImgproc.cpp @@ -31,6 +31,12 @@ * Test imgproc functions. */ +/*! + \example testImgproc.cpp + + \brief Test imgproc functions. +*/ + #include #include #include @@ -40,15 +46,13 @@ #include #include -/*! - \example testImgproc.cpp - - \brief Test imgproc functions. -*/ - // List of allowed command line options #define GETOPTARGS "cdi:o:h" +#ifdef ENABLE_VISP_NAMESPACE +using namespace VISP_NAMESPACE_NAME; +#endif + void usage(const char *name, const char *badparam, std::string ipath, std::string opath, std::string user); bool getOptions(int argc, const char **argv, std::string &ipath, std::string &opath, std::string user); diff --git a/modules/tracker/blob/include/visp3/blob/vpDot.h b/modules/tracker/blob/include/visp3/blob/vpDot.h index 1b52904b82..aa45203df8 100644 --- a/modules/tracker/blob/include/visp3/blob/vpDot.h +++ b/modules/tracker/blob/include/visp3/blob/vpDot.h @@ -62,18 +62,6 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpDot; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, VISP_NAMESPACE_ADDRESSING vpDot &d); - -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpDot @@ -316,7 +304,7 @@ class VISP_EXPORT vpDot : public vpTracker vpDot &operator=(const vpDot &d); bool operator==(const vpDot &d) const; bool operator!=(const vpDot &d) const; - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, vpDot &d); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpDot &d); void print(std::ostream &os) { os << *this << std::endl; } diff --git a/modules/tracker/blob/include/visp3/blob/vpDot2.h b/modules/tracker/blob/include/visp3/blob/vpDot2.h index 2a9f239990..063e096b9c 100644 --- a/modules/tracker/blob/include/visp3/blob/vpDot2.h +++ b/modules/tracker/blob/include/visp3/blob/vpDot2.h @@ -56,18 +56,6 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpDot2; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, VISP_NAMESPACE_ADDRESSING vpDot2 &d); - -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpDot2 @@ -259,7 +247,7 @@ class VISP_EXPORT vpDot2 : public vpTracker unsigned int gray_lvl_max, unsigned int size = 0); vpDot2 &operator=(const vpDot2 &twinDot); - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, vpDot2 &d); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpDot2 &d); void print(std::ostream &os) { os << *this << std::endl; } void searchDotsInArea(const vpImage &I, int area_u, int area_v, unsigned int area_w, diff --git a/modules/tracker/blob/src/dots/vpDot.cpp b/modules/tracker/blob/src/dots/vpDot.cpp index 29ef78a697..babd671320 100644 --- a/modules/tracker/blob/src/dots/vpDot.cpp +++ b/modules/tracker/blob/src/dots/vpDot.cpp @@ -946,13 +946,13 @@ void vpDot::display(const vpImage &I, const vpImagePoint &cog, const std } } -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - /*! Writes the dot center of gravity coordinates in the frame (i,j) (For more details about the orientation of the frame see the vpImagePoint documentation) to the stream \e os, and returns a reference to the stream. */ -VISP_EXPORT std::ostream &operator<<(std::ostream &os, VISP_NAMESPACE_ADDRESSING vpDot &d) { return (os << "(" << d.getCog() << ")"); }; +VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpDot &d) { return (os << "(" << d.getCog() << ")"); }; + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/tracker/blob/src/dots/vpDot2.cpp b/modules/tracker/blob/src/dots/vpDot2.cpp index e753135714..4eb82ef252 100644 --- a/modules/tracker/blob/src/dots/vpDot2.cpp +++ b/modules/tracker/blob/src/dots/vpDot2.cpp @@ -2505,13 +2505,13 @@ void vpDot2::display(const vpImage &I, const vpImagePoint &cog, const st } } -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - /*! Writes the dot center of gravity coordinates in the frame (i,j) (For more details about the orientation of the frame see the vpImagePoint documentation) to the stream \e os, and returns a reference to the stream. */ VISP_EXPORT std::ostream &operator<<(std::ostream &os, VISP_NAMESPACE_ADDRESSING vpDot2 &d) { return (os << "(" << d.getCog() << ")"); } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/tracker/me/include/visp3/me/vpMeSite.h b/modules/tracker/me/include/visp3/me/vpMeSite.h index 9de3ea2eda..a801b97876 100644 --- a/modules/tracker/me/include/visp3/me/vpMeSite.h +++ b/modules/tracker/me/include/visp3/me/vpMeSite.h @@ -48,18 +48,6 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpMeSite; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, VISP_NAMESPACE_ADDRESSING vpMeSite &vpMeS); - -#if defined(ENABLE_VISP_NAMESPACE) -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpMeSite @@ -333,7 +321,7 @@ class VISP_EXPORT vpMeSite /*! * ostream operator. */ - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, vpMeSite &vpMeS); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpMeSite &vpMeS); // Static functions /*! diff --git a/modules/tracker/me/src/moving-edges/vpMeSite.cpp b/modules/tracker/me/src/moving-edges/vpMeSite.cpp index 068dfb18df..79b8cc2f5b 100644 --- a/modules/tracker/me/src/moving-edges/vpMeSite.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeSite.cpp @@ -445,11 +445,11 @@ void vpMeSite::display(const vpImage &I, const double &i, const double & } } -#if defined(ENABLE_VISP_NAMESPACE) -} -#endif - -VISP_EXPORT std::ostream &operator<<(std::ostream &os, VISP_NAMESPACE_ADDRESSING vpMeSite &vpMeS) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpMeSite &vpMeS) { return (os << "Alpha: " << vpMeS.m_alpha << " Convolution: " << vpMeS.m_convlt << " Weight: " << vpMeS.m_weight << " Threshold: " << vpMeS.m_contrastThreshold); } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h index 34c56a32b2..d148f40357 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMoment.h @@ -54,19 +54,8 @@ namespace VISP_NAMESPACE_NAME class vpMomentObject; class vpMomentDatabase; class vpFeatureMomentDatabase; -class vpFeatureMoment; class vpMoment; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpFeatureMoment &featM); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpFeatureMoment * @@ -252,7 +241,7 @@ class VISP_EXPORT vpFeatureMoment : public vpBasicFeature void update(double A, double B, double C); //@} - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpFeatureMoment &featM); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpFeatureMoment &featM); }; /*! diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h index cd4e803e1a..2a2a0def55 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCInvariant.h @@ -46,18 +46,7 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpFeatureMomentCInvariant; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpFeatureMomentCInvariant &featcinv); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpFeatureMomentCInvariant * @@ -204,19 +193,8 @@ class VISP_EXPORT vpFeatureMomentCInvariant : public vpFeatureMoment namespace VISP_NAMESPACE_NAME { #endif -class vpFeatureMomentCInvariant; class vpMomentDatabase; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpFeatureMomentCInvariant &featcinv); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpFeatureMomentCInvariant * @@ -361,7 +339,7 @@ class VISP_EXPORT vpFeatureMomentCInvariant : public vpFeatureMoment */ void printLsofInvariants(std::ostream &os) const; - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpFeatureMomentCInvariant &featcinv); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpFeatureMomentCInvariant &featcinv); }; #ifdef ENABLE_VISP_NAMESPACE } diff --git a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h index 7298805e38..46db843ea7 100644 --- a/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h +++ b/modules/visual_features/include/visp3/visual_features/vpFeatureMomentCentered.h @@ -47,18 +47,7 @@ namespace VISP_NAMESPACE_NAME { #endif class vpMomentDatabase; -class vpFeatureMomentCentered; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpFeatureMomentCentered &v); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpFeatureMomentCentered * @@ -131,7 +120,7 @@ class VISP_EXPORT vpFeatureMomentCentered : public vpFeatureMoment return "vpFeatureMomentCentered"; } - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpFeatureMomentCentered &v); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpFeatureMomentCentered &v); }; #ifdef ENABLE_VISP_NAMESPACE } diff --git a/modules/visual_features/src/visual-feature/vpFeatureMoment.cpp b/modules/visual_features/src/visual-feature/vpFeatureMoment.cpp index f6c11a5725..fc0218988d 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMoment.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMoment.cpp @@ -265,15 +265,9 @@ void vpFeatureMoment::printDependencies(std::ostream &os) const "to be implemented in the derived classes!" << std::endl; } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpFeatureMoment &featM) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpFeatureMoment &featM) { -#ifdef ENABLE_VISP_NAMESPACE - using namespace VISP_NAMESPACE_NAME; -#endif /* * - A static_cast is forced here since interaction() defined in vpBasicFeature() * is not const. But introducing const in vpBasicFeature() can break a lot of @@ -285,3 +279,7 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDR Lcomplete.matlabPrint(os); return os; } + +#ifdef ENABLE_VISP_NAMESPACE +} +#endif diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentCInvariant.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentCInvariant.cpp index c700446ba9..a0b5e76103 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentCInvariant.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentCInvariant.cpp @@ -694,15 +694,12 @@ void vpFeatureMomentCInvariant::printLsofInvariants(std::ostream &os) const os << std::endl; } } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif /*! * \relates vpFeatureMomentCInvariant * Print all the interaction matrices of visual features */ -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpFeatureMomentCInvariant &featcinv) +std::ostream &operator<<(std::ostream &os, const vpFeatureMomentCInvariant &featcinv) { // Print L for c1 .. c10 for (unsigned int i = 0; i < 10; ++i) { @@ -728,4 +725,7 @@ std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpFea return os; } +#ifdef ENABLE_VISP_NAMESPACE +} +#endif #endif diff --git a/modules/visual_features/src/visual-feature/vpFeatureMomentCentered.cpp b/modules/visual_features/src/visual-feature/vpFeatureMomentCentered.cpp index dc77ef1446..23009a4341 100644 --- a/modules/visual_features/src/visual-feature/vpFeatureMomentCentered.cpp +++ b/modules/visual_features/src/visual-feature/vpFeatureMomentCentered.cpp @@ -319,19 +319,13 @@ void vpFeatureMomentCentered::compute_interaction() } #endif // #ifdef VISP_MOMENTS_COMBINE_MATRICES } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif /*! * \relates vpFeatureMomentCentered * Print all the interaction matrices of visual features */ -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpFeatureMomentCentered &mu) +std::ostream &operator<<(std::ostream &os, const vpFeatureMomentCentered &mu) { -#ifdef ENABLE_VISP_NAMESPACE - using namespace VISP_NAMESPACE_NAME; -#endif vpTRACE(" << Ls - CENTRED MOMENTS >>"); unsigned int order_m_1 = (unsigned int)(mu.order - 1); for (unsigned int i = 0; i < order_m_1; i++) { @@ -342,3 +336,6 @@ std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpFea } return os; } +#ifdef ENABLE_VISP_NAMESPACE +} +#endif diff --git a/modules/vs/include/visp3/vs/vpAdaptiveGain.h b/modules/vs/include/visp3/vs/vpAdaptiveGain.h index 2425cd1aa6..124eeaf604 100644 --- a/modules/vs/include/visp3/vs/vpAdaptiveGain.h +++ b/modules/vs/include/visp3/vs/vpAdaptiveGain.h @@ -46,19 +46,8 @@ namespace VISP_NAMESPACE_NAME { #endif -class vpAdaptiveGain; class vpColVector; -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -// Forward declaration to have the operator in the global namespace -std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpAdaptiveGain &lambda); -#ifdef ENABLE_VISP_NAMESPACE -namespace VISP_NAMESPACE_NAME -{ -#endif /*! * \class vpAdaptiveGain * @@ -316,7 +305,7 @@ class VISP_EXPORT vpAdaptiveGain * \param os : The stream where to print the adaptive gain parameters. * \param lambda : The adaptive gain containing the parameters to print. */ - friend VISP_EXPORT std::ostream &::operator<<(std::ostream &os, const vpAdaptiveGain &lambda); + friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpAdaptiveGain &lambda); }; #ifdef ENABLE_VISP_NAMESPACE } diff --git a/modules/vs/src/vpAdaptiveGain.cpp b/modules/vs/src/vpAdaptiveGain.cpp index f1d6e36e54..4f8df7a29b 100644 --- a/modules/vs/src/vpAdaptiveGain.cpp +++ b/modules/vs/src/vpAdaptiveGain.cpp @@ -142,14 +142,14 @@ double vpAdaptiveGain::operator()(void) const { return this->limitValue(); } double vpAdaptiveGain::operator()(const vpColVector &x) const { return this->value(x.infinityNorm()); } -#ifdef ENABLE_VISP_NAMESPACE -} -#endif - -VISP_EXPORT std::ostream &operator<<(std::ostream &os, const VISP_NAMESPACE_ADDRESSING vpAdaptiveGain &lambda) +VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpAdaptiveGain &lambda) { os << "Zero= " << lambda.coeff_a + lambda.coeff_c << "\tInf= " << lambda.coeff_c << "\tSlope= " << lambda.coeff_a * lambda.coeff_b; return os; } + +#ifdef ENABLE_VISP_NAMESPACE +} +#endif