diff --git a/CMakeLists.txt b/CMakeLists.txt index 34ac969235..bb35966907 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -541,6 +541,9 @@ VP_OPTION(ENABLE_MOMENTS_COMBINE_MATRICES "" "" "Use linear combination of matr VP_OPTION(ENABLE_TEST_WITHOUT_DISPLAY "" "" "Don't use display feature when testing" "" ON) VP_OPTION(ENABLE_FULL_DOC "" "" "Build doc with internal classes that are by default not part of the doc" "" OFF) +# Allow introduction of "visp" namespace. By default disabled to keep compat with previous versions +VP_OPTION(ENABLE_VISP_NAMESPACE "" "" "Enable visp namespace" "" OFF) + if(ENABLE_SOLUTION_FOLDERS) set_property(GLOBAL PROPERTY USE_FOLDERS ON) set_property(GLOBAL PROPERTY PREDEFINED_TARGETS_FOLDER "CMakeTargets") @@ -1603,6 +1606,7 @@ status(" To be built:" VISP_MODULES_BUILD THEN ${VISP_MOD status(" Disabled:" VISP_MODULES_DISABLED_USER THEN ${VISP_MODULES_DISABLED_USER_ST} ELSE "-") status(" Disabled by dependency:" VISP_MODULES_DISABLED_AUTO THEN ${VISP_MODULES_DISABLED_AUTO_ST} ELSE "-") status(" Unavailable:" VISP_MODULES_DISABLED_FORCE THEN ${VISP_MODULES_DISABLED_FORCE_ST} ELSE "-") +status(" Enable visp namespace:" ENABLE_VISP_NAMESPACE THEN "yes" ELSE "no") # ========================== Android details ========================== if(ANDROID) diff --git a/cmake/templates/VISPConfig.cmake.in b/cmake/templates/VISPConfig.cmake.in index b51ca8afa2..23c27cebe5 100644 --- a/cmake/templates/VISPConfig.cmake.in +++ b/cmake/templates/VISPConfig.cmake.in @@ -189,6 +189,7 @@ set(VISP_BIN_INSTALL_PATH "@VISP_BIN_INSTALL_PATH@") #---------------------------------------------------------------------- # Remember VISP third party libs configuration #---------------------------------------------------------------------- +set(ENABLE_VISP_NAMESPACE "@ENABLE_VISP_NAMESPACE@") set(VISP_HAVE_AFMA4 "@VISP_HAVE_AFMA4@") set(VISP_HAVE_AFMA6 "@VISP_HAVE_AFMA6@") set(VISP_HAVE_APRILTAG "@VISP_HAVE_APRILTAG@") diff --git a/cmake/templates/vpConfig.h.in b/cmake/templates/vpConfig.h.in index fcfc2df44d..2bdcb71606 100644 --- a/cmake/templates/vpConfig.h.in +++ b/cmake/templates/vpConfig.h.in @@ -112,6 +112,9 @@ VISP_VERSION_MINOR, \ VISP_VERSION_PATCH) +// Defined if the user wants to protect the classes in a dedicated visp namespace +#cmakedefine ENABLE_VISP_NAMESPACE + // Enable debug and trace printings #cmakedefine VP_TRACE #cmakedefine VP_DEBUG diff --git a/modules/core/include/visp3/core/vpArray2D.h b/modules/core/include/visp3/core/vpArray2D.h index d466f451b6..ca5342de7d 100644 --- a/modules/core/include/visp3/core/vpArray2D.h +++ b/modules/core/include/visp3/core/vpArray2D.h @@ -46,8 +46,23 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +template class vpArray2D; +} +#endif + #ifdef VISP_HAVE_NLOHMANN_JSON #include +#if defined(ENABLE_VISP_NAMESPACE) +//template +template +void from_json(const nlohmann::json &j, visp::vpArray2D &array); +//template +template +void to_json(nlohmann::json &j, const visp::vpArray2D &array); +#endif #endif /*! @@ -122,7 +137,11 @@ * } * \endcode */ -template class vpArray2D +template class +#if defined(ENABLE_VISP_NAMESPACE) +visp:: +#endif +vpArray2D { protected: //! Number of rows in the array @@ -1018,10 +1037,10 @@ template class vpArray2D #ifdef VISP_HAVE_NLOHMANN_JSON //template template - friend void from_json(const nlohmann::json &j, vpArray2D &array); + friend void ::from_json(const nlohmann::json &j, vpArray2D &array); //template template - friend void to_json(nlohmann::json &j, const vpArray2D &array); + friend void ::to_json(nlohmann::json &j, const vpArray2D &array); #endif /*! @@ -1082,6 +1101,11 @@ template class vpArray2D //@} }; +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! Return the array min value. */ @@ -1323,13 +1347,23 @@ template <> inline bool vpArray2D::operator==(const vpArray2D &A) * \relates vpArray2D */ template bool vpArray2D::operator!=(const vpArray2D &A) const { return !(*this == A); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #ifdef VISP_HAVE_NLOHMANN_JSON - - template -inline void from_json(const nlohmann::json &j, vpArray2D &array) +inline void from_json(const nlohmann::json &j, +#if defined(ENABLE_VISP_NAMESPACE) +visp::vpArray2D &array +#else +vpArray2D &array +#endif +) { +#if defined(ENABLE_VISP_NAMESPACE) + using namespace visp; +#endif if (j.is_array()) { const unsigned int nrows = static_cast(j.size()); if (nrows == 0) { // Initialize an empty array, Finished @@ -1381,7 +1415,13 @@ inline void from_json(const nlohmann::json &j, vpArray2D &array) template -inline void to_json(nlohmann::json &j, const vpArray2D &array) +inline void to_json(nlohmann::json &j, +#if defined(ENABLE_VISP_NAMESPACE) +const visp::vpArray2D &array +#else +const vpArray2D &array +#endif +) { j = { {"cols", array.colNum}, diff --git a/modules/core/include/visp3/core/vpCPUFeatures.h b/modules/core/include/visp3/core/vpCPUFeatures.h index 53878cf6b4..1decf4e2df 100644 --- a/modules/core/include/visp3/core/vpCPUFeatures.h +++ b/modules/core/include/visp3/core/vpCPUFeatures.h @@ -31,16 +31,20 @@ * CPU features (hardware capabilities). */ -#ifndef _vpCPUFeatures_h_ -#define _vpCPUFeatures_h_ - /*! \file vpCPUFeatures.h \brief Check CPU features (hardware capabilities). */ +#ifndef _vpCPUFeatures_h_ +#define _vpCPUFeatures_h_ + #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \ingroup group_core_cpu_features \brief Check CPU features (hardware capabilities). @@ -77,5 +81,7 @@ VISP_EXPORT size_t getCPUCacheL3(); #endif VISP_EXPORT void printCPUInfo(); } // namespace vpCPUFeatures - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpCameraParameters.h b/modules/core/include/visp3/core/vpCameraParameters.h index 1a9f2b283d..649a4567f3 100644 --- a/modules/core/include/visp3/core/vpCameraParameters.h +++ b/modules/core/include/visp3/core/vpCameraParameters.h @@ -48,8 +48,19 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +class vpCameraParameters; +} +#endif + #ifdef VISP_HAVE_NLOHMANN_JSON #include +#if defined(ENABLE_VISP_NAMESPACE) +void to_json(nlohmann::json &j, const visp::vpCameraParameters &cam); +void from_json(const nlohmann::json &j, visp::vpCameraParameters &cam); +#endif #endif /*! @@ -300,7 +311,12 @@ {"model":"perspectiveWithoutDistortion","px":801.0,"py":802.0,"u0":325.0,"v0":245.0} \endcode */ -class VISP_EXPORT vpCameraParameters + +class VISP_EXPORT +#if defined(ENABLE_VISP_NAMESPACE) + visp:: +#endif + vpCameraParameters { friend class vpMeterPixelConversion; friend class vpPixelMeterConversion; @@ -442,18 +458,26 @@ class VISP_EXPORT vpCameraParameters vpCameraParametersProjType m_projModel; //!< used projection model #ifdef VISP_HAVE_NLOHMANN_JSON - friend void to_json(nlohmann::json &j, const vpCameraParameters &cam); - friend void from_json(const nlohmann::json &j, vpCameraParameters &cam); + friend void ::to_json(nlohmann::json &j, const vpCameraParameters &cam); + friend void ::from_json(const nlohmann::json &j, vpCameraParameters &cam); #endif }; #ifdef VISP_HAVE_NLOHMANN_JSON #include +#if defined(ENABLE_VISP_NAMESPACE) +NLOHMANN_JSON_SERIALIZE_ENUM(visp::vpCameraParameters::vpCameraParametersProjType, { + {visp::vpCameraParameters::perspectiveProjWithoutDistortion, "perspectiveWithoutDistortion"}, + {visp::vpCameraParameters::perspectiveProjWithDistortion, "perspectiveWithDistortion"}, + {visp::vpCameraParameters::ProjWithKannalaBrandtDistortion, "kannalaBrandtDistortion"} + }); +#else NLOHMANN_JSON_SERIALIZE_ENUM(vpCameraParameters::vpCameraParametersProjType, { {vpCameraParameters::perspectiveProjWithoutDistortion, "perspectiveWithoutDistortion"}, {vpCameraParameters::perspectiveProjWithDistortion, "perspectiveWithDistortion"}, {vpCameraParameters::ProjWithKannalaBrandtDistortion, "kannalaBrandtDistortion"} }); +#endif /** * \brief Converts camera parameters into a JSON representation. @@ -461,8 +485,17 @@ NLOHMANN_JSON_SERIALIZE_ENUM(vpCameraParameters::vpCameraParametersProjType, { * \param j The resulting JSON object. * \param cam The camera to serialize. */ -inline void to_json(nlohmann::json &j, const vpCameraParameters &cam) +inline void to_json(nlohmann::json &j, +#if defined(ENABLE_VISP_NAMESPACE) +const visp::vpCameraParameters &cam +#else +const vpCameraParameters &cam +#endif +) { +#if defined(ENABLE_VISP_NAMESPACE) + using namespace visp; +#endif j["px"] = cam.m_px; j["py"] = cam.m_py; j["u0"] = cam.m_u0; @@ -514,8 +547,17 @@ inline void to_json(nlohmann::json &j, const vpCameraParameters &cam) * \param j The json object to deserialize. * \param cam The modified camera. */ -inline void from_json(const nlohmann::json &j, vpCameraParameters &cam) +inline void from_json(const nlohmann::json &j, +#if defined(ENABLE_VISP_NAMESPACE) +visp::vpCameraParameters &cam +#else +vpCameraParameters &cam +#endif +) { +#if defined(ENABLE_VISP_NAMESPACE) + using namespace visp; +#endif const double px = j.at("px").get(); const double py = j.at("py").get(); const double u0 = j.at("u0").get(); @@ -544,5 +586,4 @@ inline void from_json(const nlohmann::json &j, vpCameraParameters &cam) } } #endif - #endif diff --git a/modules/core/include/visp3/core/vpCannyEdgeDetection.h b/modules/core/include/visp3/core/vpCannyEdgeDetection.h index c9f7228fc4..2f319d770c 100644 --- a/modules/core/include/visp3/core/vpCannyEdgeDetection.h +++ b/modules/core/include/visp3/core/vpCannyEdgeDetection.h @@ -45,114 +45,17 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif +/** + * \brief Class that implements the Canny's edge detector. + * It is possible to use a boolean mask to ignore some pixels of + * the input gray-scale image. + */ class VISP_EXPORT vpCannyEdgeDetection { -private: - typedef enum EdgeType - { - STRONG_EDGE, /*!< This pixel exceeds the upper threshold of the double hysteresis phase, it is thus for sure an edge point.*/ - WEAK_EDGE,/*!< This pixel is between the lower and upper threshold of the double hysteresis phase, it is an edge point only if it is linked at some point to an edge point.*/ - ON_CHECK /*!< This pixel is currently tested to know if it is linked to a strong edge point.*/ - } EdgeType; - - // Filtering + gradient methods choice - vpImageFilter::vpCannyFilteringAndGradientType m_filteringAndGradientType; /*!< Choice of the filter and - gradient operator to apply before the edge detection step*/ - - // // Gaussian smoothing attributes - int m_gaussianKernelSize; /*!< Size of the Gaussian filter kernel used to smooth the input image. Must be an odd number.*/ - float m_gaussianStdev; /*!< Standard deviation of the Gaussian filter.*/ - vpArray2D m_fg; /*!< Array that contains the Gaussian kernel.*/ - - // // Gradient computation attributes - bool m_areGradientAvailable; /*!< Set to true if the user provides the gradient images, false otherwise. In the latter case, the class will compute the gradients.*/ - unsigned int m_gradientFilterKernelSize; /*!< The size of the Sobel kernels used to compute the gradients of the image.*/ - vpArray2D m_gradientFilterX; /*!< Array that contains the gradient filter kernel (Sobel or Scharr) along the X-axis.*/ - vpArray2D m_gradientFilterY; /*!< Array that contains the gradient filter kernel (Sobel or Scharr) along the Y-axis.*/ - vpImage m_dIx; /*!< X-axis gradient.*/ - vpImage m_dIy; /*!< Y-axis gradient.*/ - - // // Edge thining attributes - std::map, float> m_edgeCandidateAndGradient; /*!< Map that contains point image coordinates and corresponding gradient value.*/ - - // // Hysteresis thresholding attributes - float m_lowerThreshold; /*!< Lower threshold for the hysteresis step. If negative, it will be deduced - as from m_upperThreshold. */ - float m_lowerThresholdRatio; /*!< If the thresholds must be computed, the ratio of the upper threshold the lower - threshold is equal: m_lowerThreshold = m_lowerThresholdRatio * m_upperThreshold. */ - float m_upperThreshold; /*!< Upper threshold for the hysteresis step.*/ - float m_upperThresholdRatio; /*!< If the thresholds must be computed, the ratio of pixels of the gradient image that - must be lower than the upper threshold \b m_upperThreshold.*/ - - // // Edge tracking attributes - std::map, EdgeType> m_edgePointsCandidates; /*!< Map that contains the strong edge points, i.e. the points for which we know for sure they are edge points, - and the weak edge points, i.e. the points for which we still must determine if they are actual edge points.*/ - vpImage m_edgeMap; /*!< Final edge map that results from the whole Canny algorithm.*/ - const vpImage *mp_mask; /*!< Mask that permits to consider only the pixels for which the mask is true.*/ - - /** @name Constructors and initialization */ - //@{ - /** - * \brief Initialize the Gaussian filters used to filter the input image. - */ - void initGaussianFilters(); - - /** - * \brief Initialize the gradient filters (Sobel or Scharr) used to compute the input image gradients. - */ - void initGradientFilters(); - //@} - - /** @name Different steps methods */ - /** - * \brief Step 1: filtering + Step 2: gradient computation - * \details First, perform Gaussian blur to the input image. - * Then, compute the x-axis and y-axis gradients of the image. - * \param[in] I : The image we want to compute the gradients. - */ - void computeFilteringAndGradient(const vpImage &I); - - /** - * \brief Step 3: Edge thining. - * \details Perform the edge thining step. - * Perform a non-maximum suppression to keep only local maxima as edge candidates. - * \param[in] lowerThreshold Edge candidates that are below this threshold are definitely not - * edges. - */ - void performEdgeThinning(const float &lowerThreshold); - - /** - * \brief Perform hysteresis thresholding. - * \details Edge candidates that are greater than \b m_upperThreshold are saved in \b m_strongEdgePoints - * and will be kept in the final edge map. - * Edge candidates that are between \b m_lowerThreshold and \b m_upperThreshold are saved in - * \b m_weakEdgePoints and will be kept in the final edge map only if they are connected - * to a strong edge point. - * Edge candidates that are below \b m_lowerThreshold are discarded. - * \param[in] lowerThreshold Edge candidates that are below this threshold are definitely not - * edges. - * \param[in] upperThreshold Edge candidates that are greater than this threshold are classified - * as strong edges. - */ - void performHysteresisThresholding(const float &lowerThreshold, const float &upperThreshold); - - /** - * \brief Search recursively for a strong edge in the neighborhood of a weak edge. - * - * \param[in] coordinates : The coordinates we are checking. - * \return true We found a strong edge point in its 8-connected neighborhood. - * \return false We did not found a strong edge point in its 8-connected neighborhood. - */ - bool recursiveSearchForStrongEdge(const std::pair &coordinates); - - /** - * \brief Perform edge tracking. - * \details For each weak edge, we will recursively check if they are 8-connected to a strong edge point. - * If so, the weak edge will be saved in \b m_strongEdgePoints and will be kept in the final edge map. - * Otherwise, the edge point will be discarded. - */ - void performEdgeTracking(); - //@} public: /** @name Constructors and initialization */ @@ -382,5 +285,114 @@ class VISP_EXPORT vpCannyEdgeDetection mp_mask = p_mask; } //@} +private: + typedef enum EdgeType + { + STRONG_EDGE, /*!< This pixel exceeds the upper threshold of the double hysteresis phase, it is thus for sure an edge point.*/ + WEAK_EDGE,/*!< This pixel is between the lower and upper threshold of the double hysteresis phase, it is an edge point only if it is linked at some point to an edge point.*/ + ON_CHECK /*!< This pixel is currently tested to know if it is linked to a strong edge point.*/ + } EdgeType; + + // Filtering + gradient methods choice + vpImageFilter::vpCannyFilteringAndGradientType m_filteringAndGradientType; /*!< Choice of the filter and + gradient operator to apply before the edge detection step*/ + + // // Gaussian smoothing attributes + int m_gaussianKernelSize; /*!< Size of the Gaussian filter kernel used to smooth the input image. Must be an odd number.*/ + float m_gaussianStdev; /*!< Standard deviation of the Gaussian filter.*/ + vpArray2D m_fg; /*!< Array that contains the Gaussian kernel.*/ + + // // Gradient computation attributes + bool m_areGradientAvailable; /*!< Set to true if the user provides the gradient images, false otherwise. In the latter case, the class will compute the gradients.*/ + unsigned int m_gradientFilterKernelSize; /*!< The size of the Sobel kernels used to compute the gradients of the image.*/ + vpArray2D m_gradientFilterX; /*!< Array that contains the gradient filter kernel (Sobel or Scharr) along the X-axis.*/ + vpArray2D m_gradientFilterY; /*!< Array that contains the gradient filter kernel (Sobel or Scharr) along the Y-axis.*/ + vpImage m_dIx; /*!< X-axis gradient.*/ + vpImage m_dIy; /*!< Y-axis gradient.*/ + + // // Edge thining attributes + std::map, float> m_edgeCandidateAndGradient; /*!< Map that contains point image coordinates and corresponding gradient value.*/ + + // // Hysteresis thresholding attributes + float m_lowerThreshold; /*!< Lower threshold for the hysteresis step. If negative, it will be deduced + as from m_upperThreshold. */ + float m_lowerThresholdRatio; /*!< If the thresholds must be computed, the ratio of the upper threshold the lower + threshold is equal: m_lowerThreshold = m_lowerThresholdRatio * m_upperThreshold. */ + float m_upperThreshold; /*!< Upper threshold for the hysteresis step.*/ + float m_upperThresholdRatio; /*!< If the thresholds must be computed, the ratio of pixels of the gradient image that + must be lower than the upper threshold \b m_upperThreshold.*/ + + // // Edge tracking attributes + std::map, EdgeType> m_edgePointsCandidates; /*!< Map that contains the strong edge points, i.e. the points for which we know for sure they are edge points, + and the weak edge points, i.e. the points for which we still must determine if they are actual edge points.*/ + vpImage m_edgeMap; /*!< Final edge map that results from the whole Canny algorithm.*/ + const vpImage *mp_mask; /*!< Mask that permits to consider only the pixels for which the mask is true.*/ + + /** @name Constructors and initialization */ + //@{ + /** + * \brief Initialize the Gaussian filters used to filter the input image. + */ + void initGaussianFilters(); + + /** + * \brief Initialize the gradient filters (Sobel or Scharr) used to compute the input image gradients. + */ + void initGradientFilters(); + //@} + + /** @name Different steps methods */ + /** + * \brief Step 1: filtering + Step 2: gradient computation + * \details First, perform Gaussian blur to the input image. + * Then, compute the x-axis and y-axis gradients of the image. + * \param[in] I : The image we want to compute the gradients. + */ + void computeFilteringAndGradient(const vpImage &I); + + /** + * \brief Step 3: Edge thining. + * \details Perform the edge thining step. + * Perform a non-maximum suppression to keep only local maxima as edge candidates. + * \param[in] lowerThreshold Edge candidates that are below this threshold are definitely not + * edges. + */ + void performEdgeThinning(const float &lowerThreshold); + + /** + * \brief Perform hysteresis thresholding. + * \details Edge candidates that are greater than \b m_upperThreshold are saved in \b m_strongEdgePoints + * and will be kept in the final edge map. + * Edge candidates that are between \b m_lowerThreshold and \b m_upperThreshold are saved in + * \b m_weakEdgePoints and will be kept in the final edge map only if they are connected + * to a strong edge point. + * Edge candidates that are below \b m_lowerThreshold are discarded. + * \param[in] lowerThreshold Edge candidates that are below this threshold are definitely not + * edges. + * \param[in] upperThreshold Edge candidates that are greater than this threshold are classified + * as strong edges. + */ + void performHysteresisThresholding(const float &lowerThreshold, const float &upperThreshold); + + /** + * \brief Search recursively for a strong edge in the neighborhood of a weak edge. + * + * \param[in] coordinates : The coordinates we are checking. + * \return true We found a strong edge point in its 8-connected neighborhood. + * \return false We did not found a strong edge point in its 8-connected neighborhood. + */ + bool recursiveSearchForStrongEdge(const std::pair &coordinates); + + /** + * \brief Perform edge tracking. + * \details For each weak edge, we will recursively check if they are 8-connected to a strong edge point. + * If so, the weak edge will be saved in \b m_strongEdgePoints and will be kept in the final edge map. + * Otherwise, the edge point will be discarded. + */ + void performEdgeTracking(); + //@} }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpCircle.h b/modules/core/include/visp3/core/vpCircle.h index 5e76dded5f..eb382d9cd2 100644 --- a/modules/core/include/visp3/core/vpCircle.h +++ b/modules/core/include/visp3/core/vpCircle.h @@ -36,15 +36,20 @@ \brief class that defines what is a circle */ -#ifndef vpCircle_hh -#define vpCircle_hh +#ifndef _vpCircle_h_ +#define _vpCircle_h_ #include +#include #include #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpCircle * \ingroup group_core_geometry @@ -133,9 +138,6 @@ class VISP_EXPORT vpCircle : public vpForwardProjection static void computeIntersectionPoint(const vpCircle &circle, const vpCameraParameters &cam, const double &rho, const double &theta, double &i, double &j); -protected: - void init() vp_override; - public: #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) /*! @@ -165,6 +167,11 @@ class VISP_EXPORT vpCircle : public vpForwardProjection vp_deprecated double get_mu02() const { return p[4]; } //@} #endif -}; +protected: + void init() vp_override; +}; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpColVector.h b/modules/core/include/visp3/core/vpColVector.h index 18906e6522..6156651646 100644 --- a/modules/core/include/visp3/core/vpColVector.h +++ b/modules/core/include/visp3/core/vpColVector.h @@ -31,26 +31,49 @@ * Provide some simple operation on column vectors. */ +/*! + * \file vpColVector.h + * \brief definition of column vector class as well + * as a set of operations on these vector + */ + #ifndef _vpColVector_h_ #define _vpColVector_h_ -#include -#include -#include -#include -#include +#include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +class vpColVector; +} +#endif + +#ifdef VISP_HAVE_NLOHMANN_JSON +#include +#if defined(ENABLE_VISP_NAMESPACE) +void to_json(nlohmann::json &j, const visp::vpColVector &pose); +void from_json(const nlohmann::json &j, visp::vpColVector &pose); +#endif +#endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif class vpMatrix; class vpRowVector; class vpRotationVector; class vpTranslationVector; class vpPoseVector; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif -/*! - * \file vpColVector.h - * \brief definition of column vector class as well - * as a set of operations on these vector - */ +#include +#include +#include +#include +#include /*! * \class vpColVector @@ -159,7 +182,11 @@ class vpPoseVector; * {"cols":1,"data":[1.0,2.0,3.0,4.0],"rows":4,"type":"vpColVector"} * \endcode */ -class VISP_EXPORT vpColVector : public vpArray2D +class VISP_EXPORT +#if defined(ENABLE_VISP_NAMESPACE) + visp:: +#endif +vpColVector: public vpArray2D { friend class vpMatrix; @@ -270,7 +297,9 @@ class VISP_EXPORT vpColVector : public vpArray2D free(rowPtrs); rowPtrs = nullptr; } - rowNum = colNum = dsize = 0; + rowNum = 0; + colNum = 0; + dsize = 0; } /*! @@ -1332,7 +1361,7 @@ class VISP_EXPORT vpColVector : public vpArray2D * @param j : Resulting json object. * @param v : The object to convert. */ - friend void to_json(nlohmann::json &j, const vpColVector &v); + friend void ::to_json(nlohmann::json &j, const vpColVector &v); /*! * Retrieve a vpColVector object from a JSON representation. @@ -1340,7 +1369,7 @@ class VISP_EXPORT vpColVector : public vpArray2D * @param j : JSON representation to convert. * @param v : Converted object. */ - friend void from_json(const nlohmann::json &j, vpColVector &v); + friend void ::from_json(const nlohmann::json &j, vpColVector &v); #endif #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) @@ -1446,6 +1475,10 @@ class VISP_EXPORT vpColVector : public vpArray2D #endif }; +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \relates vpColVector * Allows to multiply a scalar by a column vector. @@ -1454,24 +1487,42 @@ class VISP_EXPORT vpColVector : public vpArray2D VISP_EXPORT #endif vpColVector operator*(const double &x, const vpColVector &v); +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #ifdef VISP_HAVE_NLOHMANN_JSON -inline void to_json(nlohmann::json &j, const vpColVector &v) +inline void to_json(nlohmann::json &j, +#if defined(ENABLE_VISP_NAMESPACE) +const visp::vpColVector &v +#else +const vpColVector &v +#endif +) { +#if defined(ENABLE_VISP_NAMESPACE) + using namespace visp; +#endif const vpArray2D *asArray = (vpArray2D*) & v; to_json(j, *asArray); j["type"] = "vpColVector"; } -inline void from_json(const nlohmann::json &j, vpColVector &v) +inline void from_json(const nlohmann::json &j, +#if defined(ENABLE_VISP_NAMESPACE) +visp::vpColVector &v +#else +vpColVector &v +#endif +) { +#if defined(ENABLE_VISP_NAMESPACE) + using namespace visp; +#endif vpArray2D *asArray = (vpArray2D*) & v; from_json(j, *asArray); if (v.getCols() != 1) { throw vpException(vpException::badValue, "From JSON, tried to read a 2D array into a vpColVector"); } } - - #endif - #endif diff --git a/modules/core/include/visp3/core/vpColor.h b/modules/core/include/visp3/core/vpColor.h index 509a736aa8..2f135449df 100644 --- a/modules/core/include/visp3/core/vpColor.h +++ b/modules/core/include/visp3/core/vpColor.h @@ -37,6 +37,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpColor @@ -152,7 +156,8 @@ class VISP_EXPORT vpColor : public vpRGBa { public: /*! Predefined colors identifier. */ - typedef enum { + typedef enum + { id_black = 0, /*!< Identifier associated to the predefined vpColor::black color. */ id_white, /*!< Identifier associated to the predefined vpColor::white @@ -232,7 +237,7 @@ class VISP_EXPORT vpColor : public vpRGBa that this color is not a predefined one. */ - inline vpColor() : vpRGBa(), id(id_unknown) {} + inline vpColor() : vpRGBa(), id(id_unknown) { } /*! Construct a color from its RGB values. @@ -246,8 +251,7 @@ class VISP_EXPORT vpColor : public vpRGBa inline vpColor(unsigned char r, unsigned char g, unsigned char b, vpColor::vpColorIdentifier cid = vpColor::id_unknown) : vpRGBa(r, g, b), id(cid) - { - } + { } /*! Construct a color from its RGB values and alpha channel. @@ -262,18 +266,17 @@ class VISP_EXPORT vpColor : public vpRGBa inline vpColor(unsigned char r, unsigned char g, unsigned char b, unsigned char alpha, vpColor::vpColorIdentifier cid = vpColor::id_unknown) : vpRGBa(r, g, b, alpha), id(cid) - { - } + { } /*! Construct a color with an alpha channel. \param color : RGB color. \param alpha : Alpha channel for transparency. */ - inline vpColor(const vpColor &color, unsigned char alpha) : vpRGBa(color.R, color.G, color.B, alpha), id(color.id) {} + inline vpColor(const vpColor &color, unsigned char alpha) : vpRGBa(color.R, color.G, color.B, alpha), id(color.id) { } /*! Default destructor. */ - inline virtual ~vpColor() {} + 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); @@ -367,7 +370,7 @@ vpColor const __declspec(selectany) vpColor::none = vpColor(0, 0, 0, id_unknown) const __declspec(selectany) unsigned int vpColor::nbColors = 18; /*!< Array of available colors. */ -vpColor const __declspec(selectany) vpColor::allColors[vpColor::nbColors] = {vpColor::blue, // 12 +vpColor const __declspec(selectany) vpColor::allColors[vpColor::nbColors] = { vpColor::blue, // 12 vpColor::green, // 9 vpColor::red, // 6 vpColor::cyan, // 15 @@ -384,8 +387,10 @@ vpColor const __declspec(selectany) vpColor::allColors[vpColor::nbColors] = {vpC vpColor::gray, // 3 vpColor::darkGray, // 4 vpColor::black, // 0 - vpColor::white}; // 17 + vpColor::white }; // 17 #endif - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpColorDepthConversion.h b/modules/core/include/visp3/core/vpColorDepthConversion.h index 5b34e0739d..7a5c591528 100644 --- a/modules/core/include/visp3/core/vpColorDepthConversion.h +++ b/modules/core/include/visp3/core/vpColorDepthConversion.h @@ -39,6 +39,10 @@ #include "vpCameraParameters.h" #include "vpImage.h" +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif class VISP_EXPORT vpColorDepthConversion { public: @@ -54,3 +58,6 @@ class VISP_EXPORT vpColorDepthConversion const vpHomogeneousMatrix &color_M_depth, const vpHomogeneousMatrix &depth_M_color, const vpImagePoint &from_pixel); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/include/visp3/core/vpDebug.h b/modules/core/include/visp3/core/vpDebug.h index a9329f5be6..81f648a4a8 100644 --- a/modules/core/include/visp3/core/vpDebug.h +++ b/modules/core/include/visp3/core/vpDebug.h @@ -61,6 +61,10 @@ #define VP_DEBUG_MODE 0 #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpTraceOutput @@ -131,16 +135,6 @@ */ class vpTraceOutput { -private: - const char *currentFile; // Name of the file to use in the displays - const char *currentFunc; // Name of the function to use in the displays - int currentLine; // Line to use in the displays - - // if true, output to std::cerr/stderr else std::cout/stdout - bool err; - // string to display before anything else - const char *header; - public: /*! Constructor. @@ -242,6 +236,16 @@ class vpTraceOutput fflush(stdout); } } +private: + const char *currentFile; // Name of the file to use in the displays + const char *currentFunc; // Name of the function to use in the displays + int currentLine; // Line to use in the displays + + // if true, output to std::cerr/stderr else std::cout/stdout + bool err; + // string to display before anything else + const char *header; + }; /* ------------------------------------------------------------------------- */ @@ -547,5 +551,7 @@ inline void vpDEBUG_TRACE(int /* level */, const char * /* a */, ...) { } #else #define DEFENSIF(a) (0) #endif /*#ifdef DEFENSIF*/ - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif /* #ifdef __DEBUG_HH */ diff --git a/modules/core/include/visp3/core/vpDisplay.h b/modules/core/include/visp3/core/vpDisplay.h index 822256aaf2..0b4a1fc8b8 100644 --- a/modules/core/include/visp3/core/vpDisplay.h +++ b/modules/core/include/visp3/core/vpDisplay.h @@ -31,6 +31,12 @@ * Image display. */ +/*! + * \file vpDisplay.h + * \brief Generic class for image display, also provide the interface + * with the image. + */ + #ifndef _vpDisplay_h_ #define _vpDisplay_h_ @@ -48,12 +54,10 @@ #include #include -/*! - * \file vpDisplay.h - * \brief Generic class for image display, also provide the interface - * with the image. - */ - +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpDisplay * @@ -201,21 +205,6 @@ class VISP_EXPORT vpDisplay vpDisplay::SCALE_1. */ } vpScaleType; -protected: - //! display has been initialized - bool m_displayHasBeenInitialized; - //! display position - int m_windowXPosition; - //! display position - int m_windowYPosition; - unsigned int m_width; - unsigned int m_height; - std::string m_title; - unsigned int m_scale; - vpScaleType m_scaleType; - - void setScale(vpScaleType scaleType, unsigned int width, unsigned int height); - public: vpDisplay(); vpDisplay(const vpDisplay &d); @@ -925,9 +914,26 @@ class VISP_EXPORT vpDisplay //@} #endif +protected: + //! display has been initialized + bool m_displayHasBeenInitialized; + //! display position + int m_windowXPosition; + //! display position + int m_windowYPosition; + unsigned int m_width; + unsigned int m_height; + std::string m_title; + unsigned int m_scale; + vpScaleType m_scaleType; + + void setScale(vpScaleType scaleType, unsigned int width, unsigned int height); + private: //! Get the window pixmap and put it in vpRGBa image. virtual void getImage(vpImage &I) = 0; }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpDisplayException.h b/modules/core/include/visp3/core/vpDisplayException.h index 4214b7eaf3..8aa630df69 100644 --- a/modules/core/include/visp3/core/vpDisplayException.h +++ b/modules/core/include/visp3/core/vpDisplayException.h @@ -31,19 +31,23 @@ * Exception that can be emitted by the vpDisplay class and its derivatives. */ -#ifndef _vpDisplayException_h_ -#define _vpDisplayException_h_ - /*! * \file vpDisplayException.h * \brief error that can be emitted by the vpDisplay class and its derivatives */ +#ifndef _vpDisplayException_h_ +#define _vpDisplayException_h_ + #include #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpDisplayException * \ingroup group_core_debug @@ -90,5 +94,7 @@ class VISP_EXPORT vpDisplayException : public vpException */ explicit vpDisplayException(int id) : vpException(id) { } }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpEigenConversion.h b/modules/core/include/visp3/core/vpEigenConversion.h index a5463b6bdc..8c1d898e4a 100644 --- a/modules/core/include/visp3/core/vpEigenConversion.h +++ b/modules/core/include/visp3/core/vpEigenConversion.h @@ -40,7 +40,13 @@ #endif #include -namespace vp +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +#define VISP_EIGEN_CONVERSION_NAMESPACE vp +#else +#define VISP_EIGEN_CONVERSION_NAMESPACE visp +#endif + +namespace VISP_EIGEN_CONVERSION_NAMESPACE { #ifdef VISP_HAVE_EIGEN3 /* Eigen to ViSP */ diff --git a/modules/core/include/visp3/core/vpEndian.h b/modules/core/include/visp3/core/vpEndian.h index a55ec06854..2ea849e449 100644 --- a/modules/core/include/visp3/core/vpEndian.h +++ b/modules/core/include/visp3/core/vpEndian.h @@ -36,8 +36,8 @@ \brief Determine machine endianness and define VISP_LITTLE_ENDIAN, VISP_BIG_ENDIAN and VISP_PDP_ENDIAN macros. */ -#ifndef vpEndian_h -#define vpEndian_h +#ifndef _vpEndian_h_ +#define _vpEndian_h_ // Visual Studio 2010 or previous is missing inttypes.h #if defined(_MSC_VER) && (_MSC_VER < 1700) @@ -86,6 +86,10 @@ typedef unsigned short uint16_t; #error Cannot detect host machine endianness. #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif namespace vpEndian { VISP_EXPORT uint16_t swap16bits(uint16_t val); @@ -98,5 +102,7 @@ VISP_EXPORT double swapDouble(double d); VISP_EXPORT uint16_t reinterpret_cast_uchar_to_uint16_LE(unsigned char *const ptr); } // namespace vpEndian - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpException.h b/modules/core/include/visp3/core/vpException.h index 0eedfb374c..96b40e17be 100644 --- a/modules/core/include/visp3/core/vpException.h +++ b/modules/core/include/visp3/core/vpException.h @@ -45,6 +45,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpException * \ingroup group_core_debug @@ -57,19 +61,6 @@ */ class VISP_EXPORT vpException : public std::exception { -protected: - //! Contains the error code, see the errorCodeEnum table for details. - int code; - - //! Contains an error message (can be empty) - std::string message; - - //! Set the message container - void setMessage(const char *format, va_list args); - - //! forbid the empty constructor (protected) - vpException() : code(notInitialized), message("") { } - public: enum generalExceptionEnum { @@ -143,6 +134,22 @@ class VISP_EXPORT vpException : public std::exception * Print the error structure. */ friend VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpException &art); -}; +protected: + //! Contains the error code, see the errorCodeEnum table for details. + int code; + + //! Contains an error message (can be empty) + std::string message; + + //! Set the message container + void setMessage(const char *format, va_list args); + + //! forbid the empty constructor (protected) + vpException() : code(notInitialized), message("") { } + +}; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpExponentialMap.h b/modules/core/include/visp3/core/vpExponentialMap.h index 95637be0f4..e5c3e71555 100644 --- a/modules/core/include/visp3/core/vpExponentialMap.h +++ b/modules/core/include/visp3/core/vpExponentialMap.h @@ -36,12 +36,17 @@ \brief Provides exponential map computation */ -#ifndef vpExponentialMap_h -#define vpExponentialMap_h +#ifndef _vpExponentialMap_h_ +#define _vpExponentialMap_h_ +#include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpExponentialMap @@ -92,4 +97,7 @@ class VISP_EXPORT vpExponentialMap static vpColVector inverse(const vpHomogeneousMatrix &M); static vpColVector inverse(const vpHomogeneousMatrix &M, const double &delta_t); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpFeatureDisplay.h b/modules/core/include/visp3/core/vpFeatureDisplay.h index 66c3af9643..2ec64cf9c0 100644 --- a/modules/core/include/visp3/core/vpFeatureDisplay.h +++ b/modules/core/include/visp3/core/vpFeatureDisplay.h @@ -31,14 +31,16 @@ * Interface with the image for feature display. */ -#ifndef vpFeatureDisplay_H -#define vpFeatureDisplay_H - /*! \file vpFeatureDisplay.h \brief interface with the image for feature display */ +#ifndef _vpFeatureDisplay_H_ +#define _vpFeatureDisplay_H_ + +#include + // Color / image / display #include #include @@ -47,6 +49,10 @@ // Meter/pixel conversion #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpFeatureDisplay @@ -82,5 +88,7 @@ class VISP_EXPORT vpFeatureDisplay static void displayPoint(double x, double y, const vpCameraParameters &cam, const vpImage &I, const vpColor &color = vpColor::green, unsigned int thickness = 1); }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpForceTwistMatrix.h b/modules/core/include/visp3/core/vpForceTwistMatrix.h index b7da80e2f7..f1635b7ca7 100644 --- a/modules/core/include/visp3/core/vpForceTwistMatrix.h +++ b/modules/core/include/visp3/core/vpForceTwistMatrix.h @@ -32,8 +32,19 @@ * frame to an other. */ -#ifndef vpForceTwistMatrix_h -#define vpForceTwistMatrix_h +#ifndef _vpForceTwistMatrix_h_ +#define _vpForceTwistMatrix_h_ + +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif +class vpMatrix; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #include #include @@ -41,6 +52,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpForceTwistMatrix @@ -235,6 +250,8 @@ class VISP_EXPORT vpForceTwistMatrix : public vpArray2D vp_deprecated void setIdentity(); //@} #endif -}; - + }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpForwardProjection.h b/modules/core/include/visp3/core/vpForwardProjection.h index 97e98c2cf6..845ce10209 100644 --- a/modules/core/include/visp3/core/vpForwardProjection.h +++ b/modules/core/include/visp3/core/vpForwardProjection.h @@ -31,20 +31,25 @@ * Forward projection. */ -#ifndef vpForwardProjection_H -#define vpForwardProjection_H - /*! * \file vpForwardProjection.h * \brief class that defines what is a generic geometric feature */ +#ifndef _vpForwardProjection_H_ +#define _vpForwardProjection_H_ + +#include #include #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpForwardProjection * \brief Class that defines what is a generic geometric feature. @@ -193,6 +198,16 @@ class VISP_EXPORT vpForwardProjection : public vpTracker void track(const vpHomogeneousMatrix &cMo); //@} + +public: + /** @name Public Attributes Inherited from vpForwardProjection */ + //@{ + /*! + * Feature coordinates expressed in the object frame. + */ + vpColVector oP; + //@} + protected: /** @name Protected Member Functions Inherited from vpForwardProjection */ //@{ @@ -205,17 +220,10 @@ class VISP_EXPORT vpForwardProjection : public vpTracker virtual void init() = 0; //@} -public: - /** @name Public Attributes Inherited from vpForwardProjection */ - //@{ - /*! - * Feature coordinates expressed in the object frame. - */ - vpColVector oP; - //@} - private: vpForwardProjectionDeallocatorType deallocate; }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpFrameGrabber.h b/modules/core/include/visp3/core/vpFrameGrabber.h index b13af19f45..fbb84085c9 100644 --- a/modules/core/include/visp3/core/vpFrameGrabber.h +++ b/modules/core/include/visp3/core/vpFrameGrabber.h @@ -31,18 +31,23 @@ * Frame grabbing. */ -#ifndef vpFrameGrabber_hh -#define vpFrameGrabber_hh - -#include -#include - /*! * \file vpFrameGrabber.h * \brief Base class for all video devices. It is * designed to provide a generic front end to video sources. */ +#ifndef _vpFrameGrabber_h_ +#define _vpFrameGrabber_h_ + +#include +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpFrameGrabber * @@ -95,10 +100,6 @@ class VISP_EXPORT vpFrameGrabber public: bool init; //!< Set to true if the frame grabber has been initialized. -protected: - unsigned int height; //!< Number of rows in the image. - unsigned int width; //!< Number of columns in the image. - public: /** @name Inherited functionalities from vpFramegrabber */ //@{ @@ -127,6 +128,12 @@ class VISP_EXPORT vpFrameGrabber * the memory used by a specific frame grabber */ virtual void close() = 0; -}; +protected: + unsigned int height; //!< Number of rows in the image. + unsigned int width; //!< Number of columns in the image. +}; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpFrameGrabberException.h b/modules/core/include/visp3/core/vpFrameGrabberException.h index 1229b44cb5..a8c29ea6b0 100644 --- a/modules/core/include/visp3/core/vpFrameGrabberException.h +++ b/modules/core/include/visp3/core/vpFrameGrabberException.h @@ -32,21 +32,24 @@ * derivates. */ -#ifndef _vpFrameGrabberException_h_ -#define _vpFrameGrabberException_h_ - /*! * \file vpFrameGrabberException.h * \brief error that can be emitted by the vpFrameGrabber class and its * derivates */ +#ifndef _vpFrameGrabberException_h_ +#define _vpFrameGrabberException_h_ + #include #include #include #include - +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \brief Error that can be emitted by the vpFrameGrabber class and its * derivates. @@ -88,5 +91,7 @@ class VISP_EXPORT vpFrameGrabberException : public vpException */ explicit vpFrameGrabberException(int id) : vpException(id) { } }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpGEMM.h b/modules/core/include/visp3/core/vpGEMM.h index 23837d406b..982d4bb060 100644 --- a/modules/core/include/visp3/core/vpGEMM.h +++ b/modules/core/include/visp3/core/vpGEMM.h @@ -37,6 +37,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif const vpArray2D null(0, 0); /*! @@ -443,5 +447,7 @@ inline void vpGEMM(const vpArray2D &A, const vpArray2D &B, const break; } } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpGaussianFilter.h b/modules/core/include/visp3/core/vpGaussianFilter.h index 53135dff50..2209a48441 100644 --- a/modules/core/include/visp3/core/vpGaussianFilter.h +++ b/modules/core/include/visp3/core/vpGaussianFilter.h @@ -36,13 +36,18 @@ \brief Gaussian filter class */ -#ifndef vpGaussianFilter_H -#define vpGaussianFilter_H +#ifndef _vpGaussianFilter_H_ +#define _vpGaussianFilter_H_ +#include #include #if defined(VISP_HAVE_SIMDLIB) +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpGaussianFilter @@ -63,12 +68,14 @@ class VISP_EXPORT vpGaussianFilter private: vpGaussianFilter(const vpGaussianFilter &gf); - vpGaussianFilter &operator=(const vpGaussianFilter &); + vpGaussianFilter &operator=(const vpGaussianFilter &gf); // PIMPL idiom class Impl; Impl *m_impl; }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif diff --git a/modules/core/include/visp3/core/vpHistogram.h b/modules/core/include/visp3/core/vpHistogram.h index 2e2b99fdb5..8c2d98a5d1 100644 --- a/modules/core/include/visp3/core/vpHistogram.h +++ b/modules/core/include/visp3/core/vpHistogram.h @@ -38,11 +38,12 @@ */ -#ifndef vpHistogram_h -#define vpHistogram_h +#ifndef _vpHistogram_h_ +#define _vpHistogram_h_ #include +#include #include #include #include @@ -54,6 +55,10 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpHistogram \ingroup group_core_histogram @@ -317,5 +322,7 @@ class VISP_EXPORT vpHistogram const vpImage *mp_mask; /*!< Mask that permits to consider only the pixels for which the mask is true.*/ unsigned int m_total; /*!< Cumulated number of pixels in the input image. */ }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpHistogramPeak.h b/modules/core/include/visp3/core/vpHistogramPeak.h index 8d5f63eb89..593cae001f 100644 --- a/modules/core/include/visp3/core/vpHistogramPeak.h +++ b/modules/core/include/visp3/core/vpHistogramPeak.h @@ -37,13 +37,17 @@ Class vpHistogramPeak defines a gray level histogram peak. */ -#ifndef vpHistogramPeak_h -#define vpHistogramPeak_h +#ifndef _vpHistogramPeak_h_ +#define _vpHistogramPeak_h_ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpHistogramPeak @@ -64,7 +68,7 @@ class VISP_EXPORT vpHistogramPeak vpHistogramPeak(const vpHistogramPeak &p); /*! Destructor that does nothing. */ - virtual ~vpHistogramPeak() {} + virtual ~vpHistogramPeak() { } vpHistogramPeak &operator=(const vpHistogramPeak &p); bool operator==(const vpHistogramPeak &p) const; @@ -145,5 +149,7 @@ class VISP_EXPORT vpHistogramPeak * c-basic-offset: 2 * End: */ - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpHistogramValey.h b/modules/core/include/visp3/core/vpHistogramValey.h index d0a753b17e..1ce432ef55 100644 --- a/modules/core/include/visp3/core/vpHistogramValey.h +++ b/modules/core/include/visp3/core/vpHistogramValey.h @@ -38,11 +38,15 @@ */ -#ifndef vpHistogramValey_h -#define vpHistogramValey_h +#ifndef _vpHistogramValey_h_ +#define _vpHistogramValey_h_ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpHistogramValey @@ -139,5 +143,7 @@ class VISP_EXPORT vpHistogramValey : vpHistogramPeak * c-basic-offset: 2 * End: */ - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpHomogeneousMatrix.h b/modules/core/include/visp3/core/vpHomogeneousMatrix.h index 6eb0e353de..10dcfbe7f7 100644 --- a/modules/core/include/visp3/core/vpHomogeneousMatrix.h +++ b/modules/core/include/visp3/core/vpHomogeneousMatrix.h @@ -39,6 +39,16 @@ #ifndef _vpHomogeneousMatrix_h_ #define _vpHomogeneousMatrix_h_ +#include +#include + +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + class vpTranslationVector; class vpPoseVector; class vpMatrix; @@ -48,8 +58,9 @@ class vpThetaUVector; class vpQuaternionVector; class vpPoint; -#include -#include +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #include #include @@ -57,8 +68,19 @@ class vpPoint; #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +class vpHomogeneousMatrix; +} +#endif + #ifdef VISP_HAVE_NLOHMANN_JSON #include +#if defined(ENABLE_VISP_NAMESPACE) +void to_json(nlohmann::json &j, const visp::vpHomogeneousMatrix &T); +void from_json(const nlohmann::json &j, visp::vpHomogeneousMatrix &T); +#endif #endif /*! @@ -195,7 +217,11 @@ class vpPoint; {"cols":4,"data":[0.0,0.0,-1.0,0.1,0.0,-1.0,0.0,0.2,-1.0,0.0,0.0,0.3,0.0,0.0,0.0,1.0],"rows":4,"type":"vpHomogeneousMatrix"} \endcode */ -class VISP_EXPORT vpHomogeneousMatrix : public vpArray2D +class VISP_EXPORT +#if defined(ENABLE_VISP_NAMESPACE) + visp:: +#endif +vpHomogeneousMatrix: public vpArray2D { public: vpHomogeneousMatrix(); @@ -379,8 +405,8 @@ class VISP_EXPORT vpHomogeneousMatrix : public vpArray2D public: static const std::string jsonTypeName; private: - friend void to_json(nlohmann::json &j, const vpHomogeneousMatrix &cam); - friend void from_json(const nlohmann::json &j, vpHomogeneousMatrix &T); + friend void ::to_json(nlohmann::json &j, const vpHomogeneousMatrix &T); + friend void ::from_json(const nlohmann::json &j, vpHomogeneousMatrix &T); // Conversion helper function to avoid circular dependencies and MSVC errors that are not exported in the DLL void parse_json(const nlohmann::json &j); void convert_to_json(nlohmann::json &j) const; @@ -410,11 +436,23 @@ class VISP_EXPORT vpHomogeneousMatrix : public vpArray2D }; #ifdef VISP_HAVE_NLOHMANN_JSON -inline void to_json(nlohmann::json &j, const vpHomogeneousMatrix &T) +inline void to_json(nlohmann::json &j, +#if defined(ENABLE_VISP_NAMESPACE) +const visp::vpHomogeneousMatrix &T +#else +const vpHomogeneousMatrix &T +#endif +) { T.convert_to_json(j); } -inline void from_json(const nlohmann::json &j, vpHomogeneousMatrix &T) +inline void from_json(const nlohmann::json &j, +#if defined(ENABLE_VISP_NAMESPACE) +visp::vpHomogeneousMatrix &T +#else +vpHomogeneousMatrix &T +#endif +) { T.parse_json(j); } diff --git a/modules/core/include/visp3/core/vpImage.h b/modules/core/include/visp3/core/vpImage.h index a3158ec9d9..7b971486fc 100644 --- a/modules/core/include/visp3/core/vpImage.h +++ b/modules/core/include/visp3/core/vpImage.h @@ -66,6 +66,10 @@ typedef unsigned short uint16_t; #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif class vpDisplay; /*! @@ -278,7 +282,7 @@ template class vpImage Set the value \e v of an image point with coordinates (i, j), with i the row position and j the column position. */ - inline void operator()(unsigned int i, unsigned int j, const Type &v) { bitmap[i * width + j] = v; } + inline void operator()(unsigned int i, unsigned int j, const Type &v) { bitmap[(i * width) + j] = v; } /*! Get the value of an image point. @@ -1974,8 +1978,8 @@ template <> inline unsigned char vpImage::getValue(double i, doub int64_t y_ = y >> 16; if (((y_ + 1) < height) && ((x_ + 1) < width)) { - uint16_t up = vpEndian::reinterpret_cast_uchar_to_uint16_LE(bitmap + y_ * width + x_); - uint16_t down = vpEndian::reinterpret_cast_uchar_to_uint16_LE(bitmap + (y_ + 1) * width + x_); + uint16_t up = vpEndian::reinterpret_cast_uchar_to_uint16_LE(bitmap + (y_ * width) + x_); + uint16_t down = vpEndian::reinterpret_cast_uchar_to_uint16_LE(bitmap + ((y_ + 1) * width) + x_); return static_cast((((up & 0x00FF) * rfrac + (down & 0x00FF) * rratio) * cfrac + ((up >> 8) * rfrac + (down >> 8) * rratio) * cratio) >> @@ -1985,7 +1989,7 @@ template <> inline unsigned char vpImage::getValue(double i, doub return static_cast(((row[y_][x_] * rfrac + row[y_ + 1][x_] * rratio)) >> 16); } else if ((x_ + 1) < width) { - uint16_t up = vpEndian::reinterpret_cast_uchar_to_uint16_LE(bitmap + y_ * width + x_); + uint16_t up = vpEndian::reinterpret_cast_uchar_to_uint16_LE(bitmap + (y_ * width) + x_); return static_cast(((up & 0x00FF) * cfrac + (up >> 8) * cratio) >> 16); } else { @@ -2560,5 +2564,7 @@ template void swap(vpImage &first, vpImage &second) swap(first.height, second.height); swap(first.row, second.row); } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpImageCircle.h b/modules/core/include/visp3/core/vpImageCircle.h index 80a7f167a3..c3f651bd7c 100644 --- a/modules/core/include/visp3/core/vpImageCircle.h +++ b/modules/core/include/visp3/core/vpImageCircle.h @@ -49,6 +49,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /** * \brief Class that defines a 2D circle in an image. */ @@ -141,4 +145,7 @@ class VISP_EXPORT vpImageCircle vpImagePoint m_center; float m_radius; }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpImageConvert.h b/modules/core/include/visp3/core/vpImageConvert.h index ad871ac208..92159df084 100644 --- a/modules/core/include/visp3/core/vpImageConvert.h +++ b/modules/core/include/visp3/core/vpImageConvert.h @@ -75,6 +75,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpImageConvert @@ -182,9 +186,9 @@ class VISP_EXPORT vpImageConvert unsigned char &b) { double dr, dg, db; - dr = floor(0.9999695 * y - 0.0009508 * (u - 128) + 1.1359061 * (v - 128)); - dg = floor(0.9999695 * y - 0.3959609 * (u - 128) - 0.5782955 * (v - 128)); - db = floor(0.9999695 * y + 2.04112 * (u - 128) - 0.0016314 * (v - 128)); + dr = floor(((0.9999695 * y) - (0.0009508 * (u - 128))) + (1.1359061 * (v - 128))); + dg = floor(((0.9999695 * y) - (0.3959609 * (u - 128))) - (0.5782955 * (v - 128))); + db = floor(((0.9999695 * y) + (2.04112 * (u - 128))) - (0.0016314 * (v - 128))); dr = dr < 0. ? 0. : dr; dg = dg < 0. ? 0. : dg; @@ -270,6 +274,7 @@ class VISP_EXPORT vpImageConvert static void RGBToHSV(const unsigned char *rgb, unsigned char *hue, unsigned char *saturation, unsigned char *value, unsigned int size, bool h_full = true); +#ifndef VISP_SKIP_BAYER_CONVERSION static void demosaicBGGRToRGBaBilinear(const uint8_t *bggr, uint8_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads = 0); static void demosaicBGGRToRGBaBilinear(const uint16_t *bggr, uint16_t *rgba, unsigned int width, unsigned int height, @@ -309,6 +314,7 @@ class VISP_EXPORT vpImageConvert unsigned int nThreads = 0); static void demosaicRGGBToRGBaMalvar(const uint16_t *rggb, uint16_t *rgba, unsigned int width, unsigned int height, unsigned int nThreads = 0); +#endif private: static void computeYCbCrLUT(); @@ -329,5 +335,7 @@ class VISP_EXPORT vpImageConvert static int vpCgr[256]; static int vpCbb[256]; }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpImageException.h b/modules/core/include/visp3/core/vpImageException.h index 9770d62326..45ee9ab972 100644 --- a/modules/core/include/visp3/core/vpImageException.h +++ b/modules/core/include/visp3/core/vpImageException.h @@ -31,21 +31,24 @@ * Exceptions that can be emitted by the vpImage class and its derivatives. */ -#ifndef _vpImageException_h_ -#define _vpImageException_h_ - /*! * \file vpImageException.h * \brief error that can be emitted by the vpImage class and its derivatives */ +#ifndef _vpImageException_h_ +#define _vpImageException_h_ + #include #include #include #include - +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpImageException * \ingroup group_core_debug @@ -90,5 +93,7 @@ class VISP_EXPORT vpImageException : public vpException */ explicit vpImageException(int id) : vpException(id) { } }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpImageFilter.h b/modules/core/include/visp3/core/vpImageFilter.h index 4ed8c57ef7..265e930d36 100644 --- a/modules/core/include/visp3/core/vpImageFilter.h +++ b/modules/core/include/visp3/core/vpImageFilter.h @@ -31,14 +31,14 @@ * Various image tools, convolution, ... */ +/*! + * \file vpImageFilter.h + * \brief Various image filter, convolution, etc... + */ + #ifndef _vpImageFilter_h_ #define _vpImageFilter_h_ - /*! - * \file vpImageFilter.h - * \brief Various image filter, convolution, etc... - */ - #include #include #include @@ -59,6 +59,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpImageFilter * @@ -68,70 +72,6 @@ */ class VISP_EXPORT vpImageFilter { -private: - /** - * \brief Resize the image \b I to the desired size and, if \b p_mask is different from nullptr, initialize - * \b I with 0s. - * - * @tparam ImageType Any numerical type (int, float, ...) - * @param p_mask If different from nullptr, a boolean mask that tells which pixels must be computed. - * @param height The desired height. - * @param width The desired width. - * @param I The image that must be resized and potentially initialized. - */ - template - static void resizeAndInitializeIfNeeded(const vpImage *p_mask, const unsigned int height, const unsigned int width, vpImage &I) - { - if (p_mask == nullptr) { - // Just need to resize the output image, values will be computed and overwrite what is inside the image - I.resize(height, width); - } - else { - // Need to reset the image because some points will not be computed - I.resize(height, width, static_cast(0)); - } - } - -/** - * \brief Indicates if the boolean mask is true at the desired coordinates. - * - * \param[in] p_mask Pointer towards the boolean mask if any or nullptr. - * \param[in] r The row index in the boolean mask. - * \param[in] c The column index in the boolean mask. - * \return true If the boolean mask is true at the desired coordinates or if \b p_mask is equal to \b nullptr. - * \return false False otherwise. - */ - static bool checkBooleanMask(const vpImage *p_mask, const unsigned int &r, const unsigned int &c) - { - bool computeVal = true; -#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher - if (p_mask != nullptr) -#else - if (p_mask != NULL) -#endif - { - computeVal = (*p_mask)[r][c]; - } - return computeVal; - } - -// Note that on ubuntu 12.04 __cplusplus is equal to 1 that's why in the next line we consider __cplusplus <= 199711L -// and not __cplusplus == 199711L -#if ((__cplusplus <= 199711L) || (defined(_MSVC_LANG) && (_MSVC_LANG == 199711L))) // Check if cxx98 - // Helper to apply the scale to the raw values of the filters - template - static void scaleFilter(vpArray2D &filter, const float &scale) - { - const unsigned int nbRows = filter.getRows(); - const unsigned int nbCols = filter.getCols(); - for (unsigned int r = 0; r < nbRows; ++r) { - for (unsigned int c = 0; c < nbCols; ++c) { - filter[r][c] = filter[r][c] * scale; - } - } - } -#endif - public: //! Canny filter backends for the edge detection operations typedef enum vpCannyBackendType @@ -259,7 +199,8 @@ class VISP_EXPORT vpImageFilter for (unsigned int c = 0; c < nbCols; ++c) { filter[r][c] = filter[r][c] * scale; } - }}; + } + }; #endif // Scales to apply to the filters to get a normalized gradient filter that gives a gradient @@ -1693,6 +1634,73 @@ class VISP_EXPORT vpImageFilter static float median(const vpImage &Isrc); static std::vector median(const vpImage &Isrc); #endif -}; +private: + /** + * \brief Resize the image \b I to the desired size and, if \b p_mask is different from nullptr, initialize + * \b I with 0s. + * + * @tparam ImageType Any numerical type (int, float, ...) + * @param p_mask If different from nullptr, a boolean mask that tells which pixels must be computed. + * @param height The desired height. + * @param width The desired width. + * @param I The image that must be resized and potentially initialized. + */ + template + static void resizeAndInitializeIfNeeded(const vpImage *p_mask, const unsigned int height, const unsigned int width, vpImage &I) + { + if (p_mask == nullptr) { + // Just need to resize the output image, values will be computed and overwrite what is inside the image + I.resize(height, width); + } + else { + // Need to reset the image because some points will not be computed + I.resize(height, width, static_cast(0)); + } + } + +/** + * \brief Indicates if the boolean mask is true at the desired coordinates. + * + * \param[in] p_mask Pointer towards the boolean mask if any or nullptr. + * \param[in] r The row index in the boolean mask. + * \param[in] c The column index in the boolean mask. + * \return true If the boolean mask is true at the desired coordinates or if \b p_mask is equal to \b nullptr. + * \return false False otherwise. + */ + static bool checkBooleanMask(const vpImage *p_mask, const unsigned int &r, const unsigned int &c) + { + bool computeVal = true; +#if ((__cplusplus >= 201103L) || (defined(_MSVC_LANG) && (_MSVC_LANG >= 201103L))) // Check if cxx11 or higher + if (p_mask != nullptr) +#else + if (p_mask != NULL) +#endif + { + computeVal = (*p_mask)[r][c]; + } + return computeVal; + } + +// Note that on ubuntu 12.04 __cplusplus is equal to 1 that's why in the next line we consider __cplusplus <= 199711L +// and not __cplusplus == 199711L +#if ((__cplusplus <= 199711L) || (defined(_MSVC_LANG) && (_MSVC_LANG == 199711L))) // Check if cxx98 + // Helper to apply the scale to the raw values of the filters + template + static void scaleFilter(vpArray2D &filter, const float &scale) + { + const unsigned int nbRows = filter.getRows(); + const unsigned int nbCols = filter.getCols(); + for (unsigned int r = 0; r < nbRows; ++r) { + for (unsigned int c = 0; c < nbCols; ++c) { + filter[r][c] = filter[r][c] * scale; + } + } + } +#endif + +}; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpImageMorphology.h b/modules/core/include/visp3/core/vpImageMorphology.h index e467f4cd2b..d7e57ed5de 100644 --- a/modules/core/include/visp3/core/vpImageMorphology.h +++ b/modules/core/include/visp3/core/vpImageMorphology.h @@ -31,14 +31,16 @@ * Morphology tools. */ -#ifndef _vpImageMorphology_h_ -#define _vpImageMorphology_h_ - /*! \file vpImageMorphology.h \brief Various mathematical morphology tools, erosion, dilatation... */ + +#ifndef _vpImageMorphology_h_ +#define _vpImageMorphology_h_ + +#include #include #include #include @@ -48,6 +50,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpImageMorphology @@ -74,33 +80,6 @@ class VISP_EXPORT vpImageMorphology diagonal) */ } vpConnexityType; -private: - /** - * \brief Modify the image by applying the \b operation on each of its elements on a 3x3 - * grid. - * - * \tparam T Either a class such as vpRGBa or a type such as double, unsigned char ... - * \param[out] I The image we want to modify. - * \param[in] null_value The value that is padded to the input image to manage the borders. - * \param[in] operation The operation to apply to its elements on a 3x3 grid. - * \param[in] connexity Either a 4-connexity, if we want to take into account only the horizontal - * and vertical neighbors, or a 8-connexity, if we want to also take into account the diagonal neighbors. - */ - template - static void imageOperation(vpImage &I, const T &null_value, const T &(*operation)(const T &, const T &), const vpConnexityType &connexity = CONNEXITY_4); - - /** - * \brief Modify the image by applying the \b operation on each of its elements on a \b size x \b size - * grid. - * - * \tparam T Any type such as double, unsigned char ... - * \param[out] I The image we want to modify. - * \param[in] operation The operation to apply to its elements on a the grid. - * \param[in] size Size of the kernel of the operation. - */ - template - static void imageOperation(vpImage &I, const T &(*operation)(const T &, const T &), const int &size = 3); - public: template static void erosion(vpImage &I, Type value, Type value_out, vpConnexityType connexity = CONNEXITY_4); @@ -159,6 +138,34 @@ class VISP_EXPORT vpImageMorphology } //@} #endif + +private: + /** + * \brief Modify the image by applying the \b operation on each of its elements on a 3x3 + * grid. + * + * \tparam T Either a class such as vpRGBa or a type such as double, unsigned char ... + * \param[out] I The image we want to modify. + * \param[in] null_value The value that is padded to the input image to manage the borders. + * \param[in] operation The operation to apply to its elements on a 3x3 grid. + * \param[in] connexity Either a 4-connexity, if we want to take into account only the horizontal + * and vertical neighbors, or a 8-connexity, if we want to also take into account the diagonal neighbors. + */ + template + static void imageOperation(vpImage &I, const T &null_value, const T &(*operation)(const T &, const T &), const vpConnexityType &connexity = CONNEXITY_4); + + /** + * \brief Modify the image by applying the \b operation on each of its elements on a \b size x \b size + * grid. + * + * \tparam T Any type such as double, unsigned char ... + * \param[out] I The image we want to modify. + * \param[in] operation The operation to apply to its elements on a the grid. + * \param[in] size Size of the kernel of the operation. + */ + template + static void imageOperation(vpImage &I, const T &(*operation)(const T &, const T &), const int &size = 3); + }; /*! @@ -529,6 +536,9 @@ void vpImageMorphology::dilatation(vpImage &I, const int &size) const T &(*operation)(const T & a, const T & b) = std::max; vpImageMorphology::imageOperation(I, operation, size); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif /* diff --git a/modules/core/include/visp3/core/vpImagePoint.h b/modules/core/include/visp3/core/vpImagePoint.h index 120385f7b1..037434d7f8 100644 --- a/modules/core/include/visp3/core/vpImagePoint.h +++ b/modules/core/include/visp3/core/vpImagePoint.h @@ -31,15 +31,15 @@ * 2D point useful for image processing */ -#ifndef _vpImagePoint_h_ -#define _vpImagePoint_h_ - /*! \file vpImagePoint.h \brief Class that defines a 2D point in an image. This class is useful for image processing */ +#ifndef _vpImagePoint_h_ +#define _vpImagePoint_h_ + #include #include // std::fabs @@ -47,6 +47,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif class vpRect; /*! @@ -378,5 +382,7 @@ class VISP_EXPORT vpImagePoint private: double i, j; }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpImageTools.h b/modules/core/include/visp3/core/vpImageTools.h index a9b0acbd33..0308b49396 100644 --- a/modules/core/include/visp3/core/vpImageTools.h +++ b/modules/core/include/visp3/core/vpImageTools.h @@ -31,9 +31,6 @@ * Image tools. */ -#ifndef vpImageTools_H -#define vpImageTools_H - /*! \file vpImageTools.h @@ -41,6 +38,9 @@ the look up table, binarisation... */ +#ifndef _vpImageTools_H_ +#define _vpImageTools_H_ + #include #ifdef VISP_HAVE_THREADS @@ -63,6 +63,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpImageTools @@ -1937,5 +1941,7 @@ inline void vpImageTools::warpLinear(const vpImage &src, const vpMatrix } } } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpIoException.h b/modules/core/include/visp3/core/vpIoException.h index 55cf163360..3c4a9e2ce7 100644 --- a/modules/core/include/visp3/core/vpIoException.h +++ b/modules/core/include/visp3/core/vpIoException.h @@ -31,20 +31,24 @@ * Exceptions that can be emitted by the vpIo class and its derivatives. */ -#ifndef _vpIoException_h_ -#define _vpIoException_h_ - /*! * \file vpIoException.h * \brief Error that can be emitted by the vpIoTools class and its derivatives. */ +#ifndef _vpIoException_h_ +#define _vpIoException_h_ + #include #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpIoException * \ingroup group_core_debug @@ -88,5 +92,7 @@ class VISP_EXPORT vpIoException : public vpException */ explicit vpIoException(int id) : vpException(id) { } }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpIoTools.h b/modules/core/include/visp3/core/vpIoTools.h index b204c83c6e..dc12e89c6f 100644 --- a/modules/core/include/visp3/core/vpIoTools.h +++ b/modules/core/include/visp3/core/vpIoTools.h @@ -31,14 +31,14 @@ * Directory management. */ -#ifndef _vpIoTools_h_ -#define _vpIoTools_h_ - /*! * \file vpIoTools.h * \brief File and directories basic tools. */ +#ifndef _vpIoTools_h_ +#define _vpIoTools_h_ + #include #include @@ -487,6 +487,10 @@ template std::vector create_npy_header(const std::vector +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! -Parse the flag values defined in a JSON object. -if the flags are defined as an int, then this is int is directly returned. -If it is defined as a combination of options (defined from an enumeration E) then the logical or of theses enum values is returned. -Beware that invalid values may be defined in the JSON object: the int value may be invalid, or the parsing of enum values may fail. + Parse the flag values defined in a JSON object. + if the flags are defined as an int, then this is int is directly returned. + If it is defined as a combination of options (defined from an enumeration E) then the logical or of theses enum values is returned. + Beware that invalid values may be defined in the JSON object: the int value may be invalid, or the parsing of enum values may fail. -\param j: the JSON object to parse + \param j: the JSON object to parse -\return an int, corresponding to the combination of boolean flags + \return an int, corresponding to the combination of boolean flags */ template @@ -68,11 +72,11 @@ int flagsFromJSON(const nlohmann::json &j) } /*! - Serialize flag values as a json array. - \param flags the value to serialize - \param options the possible values that can be contained in flags. A flag i is set if flags & options[i] != 0. + Serialize flag values as a json array. + \param flags the value to serialize + \param options the possible values that can be contained in flags. A flag i is set if flags & options[i] != 0. - \return a json object (an array) that contains the different flags of the variable flags. + \return a json object (an array) that contains the different flags of the variable flags. */ template @@ -97,7 +101,8 @@ template bool convertFromTypeAndBuildFrom(const nlohmann::json &j, T &t) { if (j["type"] == O::jsonTypeName) { - O other = j; + O other; + from_json(j, other); t.build(other); return true; } @@ -105,6 +110,8 @@ bool convertFromTypeAndBuildFrom(const nlohmann::json &j, T &t) return convertFromTypeAndBuildFrom(j, t); } } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif diff --git a/modules/core/include/visp3/core/vpLine.h b/modules/core/include/visp3/core/vpLine.h index 44082d8da2..f446976e24 100644 --- a/modules/core/include/visp3/core/vpLine.h +++ b/modules/core/include/visp3/core/vpLine.h @@ -31,19 +31,24 @@ * Line feature. */ -#ifndef vpLine_H -#define vpLine_H - /*! * \file vpLine.h * \brief class that defines what is a line */ +#ifndef _vpLine_H_ +#define _vpLine_H_ + +#include #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpLine * \ingroup group_core_geometry @@ -172,5 +177,7 @@ class VISP_EXPORT vpLine : public vpForwardProjection protected: void init() vp_override; }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpList.h b/modules/core/include/visp3/core/vpList.h index ac5ce23642..f9a8525030 100644 --- a/modules/core/include/visp3/core/vpList.h +++ b/modules/core/include/visp3/core/vpList.h @@ -31,14 +31,14 @@ * List data structure. */ -#ifndef VP_LIST_H -#define VP_LIST_H - /*! * \file vpList.h * \brief Definition of the list management class */ +#ifndef _VP_LIST_H_ +#define _VP_LIST_H_ + #include #include #include @@ -47,6 +47,10 @@ #ifndef DOXYGEN_SHOULD_SKIP_THIS +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpListElement \brief Each element of a list @@ -704,7 +708,9 @@ template void vpList::display() } std::cout << std::endl << std::endl; } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif /* #ifndef VP_LIST_H */ /* diff --git a/modules/core/include/visp3/core/vpMath.h b/modules/core/include/visp3/core/vpMath.h index 51144d17d0..017a5d8582 100644 --- a/modules/core/include/visp3/core/vpMath.h +++ b/modules/core/include/visp3/core/vpMath.h @@ -37,8 +37,8 @@ * the C mathematics library (math.h) */ -#ifndef vpMATH_HH -#define vpMATH_HH +#ifndef _vpMATH_H_ +#define _vpMATH_H_ #include @@ -92,6 +92,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + class vpPoint; class vpHomogeneousMatrix; class vpColVector; @@ -345,8 +350,8 @@ class VISP_EXPORT vpMath double delta = (end - start) / (num - 1); - for (int i = 0; i < num - 1; ++i) { - linspaced.push_back(start + delta * i); + for (int i = 0; i < (num - 1); ++i) { + linspaced.push_back(start + (delta * i)); } linspaced.push_back(end); // I want to ensure that start and end // are exactly the same as the input @@ -662,5 +667,7 @@ template <> inline unsigned int vpMath::saturate(double v) { return static_cast(vpMath::round(v)); } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpMatrix.h b/modules/core/include/visp3/core/vpMatrix.h index 00d2d8c080..aecc94bada 100644 --- a/modules/core/include/visp3/core/vpMatrix.h +++ b/modules/core/include/visp3/core/vpMatrix.h @@ -31,8 +31,30 @@ * Matrix manipulation. */ -#ifndef vpMatrix_H -#define vpMatrix_H +/*! + \file vpMatrix.h + + \brief Definition of matrix class as well as a set of operations on + these matrices. +*/ + +#ifndef _vpMatrix_H_ +#define _vpMatrix_H_ + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + +class vpRowVector; +class vpColVector; +class vpTranslationVector; +class vpHomogeneousMatrix; +class vpVelocityTwistMatrix; +class vpForceTwistMatrix; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #include #include @@ -46,19 +68,10 @@ #include #include -class vpRowVector; -class vpColVector; -class vpTranslationVector; -class vpHomogeneousMatrix; -class vpVelocityTwistMatrix; -class vpForceTwistMatrix; - -/*! - \file vpMatrix.h - - \brief Definition of matrix class as well as a set of operations on - these matrices. -*/ +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpMatrix @@ -1200,4 +1213,7 @@ __declspec(selectany) unsigned int vpMatrix::m_lapack_min_size = vpMatrix::m_lap VISP_EXPORT #endif vpMatrix operator*(const double &x, const vpMatrix &A); +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpMatrixException.h b/modules/core/include/visp3/core/vpMatrixException.h index edc9e136a1..a92505545e 100644 --- a/modules/core/include/visp3/core/vpMatrixException.h +++ b/modules/core/include/visp3/core/vpMatrixException.h @@ -40,6 +40,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpMatrixException * \ingroup group_core_debug @@ -99,5 +103,7 @@ class VISP_EXPORT vpMatrixException : public vpException */ explicit vpMatrixException(int id) : vpException(id) { } }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpMeterPixelConversion.h b/modules/core/include/visp3/core/vpMeterPixelConversion.h index 23f14744d2..5666e0a62d 100644 --- a/modules/core/include/visp3/core/vpMeterPixelConversion.h +++ b/modules/core/include/visp3/core/vpMeterPixelConversion.h @@ -31,15 +31,14 @@ * Meter to pixel conversion. */ -#ifndef _vpMeterPixelConversion_h_ -#define _vpMeterPixelConversion_h_ - /*! \file vpMeterPixelConversion.h \brief Meter to pixel conversion. - */ +#ifndef _vpMeterPixelConversion_h_ +#define _vpMeterPixelConversion_h_ + #include #include #include @@ -51,6 +50,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpMeterPixelConversion @@ -321,9 +324,9 @@ class VISP_EXPORT vpMeterPixelConversion double theta2 = theta * theta, theta3 = theta2 * theta, theta4 = theta2 * theta2, theta5 = theta4 * theta, theta6 = theta3 * theta3, theta7 = theta6 * theta, theta8 = theta4 * theta4, theta9 = theta8 * theta; - double r_d = theta + k[0] * theta3 + k[1] * theta5 + k[2] * theta7 + k[3] * theta9; + double r_d = theta + (k[0] * theta3) + (k[1] * theta5) + (k[2] * theta7) + (k[3] * theta9); - double scale = (std::fabs(r) < std::numeric_limits::epsilon()) ? 1.0 : r_d / r; + double scale = (std::fabs(r) < std::numeric_limits::epsilon()) ? 1.0 : (r_d / r); double x_d = x * scale; double y_d = y * scale; @@ -353,5 +356,7 @@ class VISP_EXPORT vpMeterPixelConversion //@} #endif }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpMouseButton.h b/modules/core/include/visp3/core/vpMouseButton.h index 3d68601f20..7eb197937b 100644 --- a/modules/core/include/visp3/core/vpMouseButton.h +++ b/modules/core/include/visp3/core/vpMouseButton.h @@ -31,11 +31,15 @@ * Color definition. */ -#ifndef vpMouseButton_h -#define vpMouseButton_h +#ifndef _vpMouseButton_h_ +#define _vpMouseButton_h_ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpMouseButton \ingroup group_gui_display @@ -44,12 +48,15 @@ class VISP_EXPORT vpMouseButton { public: - typedef enum { + typedef enum + { button1 = 1, /*!< Mouse left button. */ button2 = 2, /*!< Mouse middle button, or roll. */ button3 = 3, /*!< Mouse right button. */ none = 0 /*!< No button. */ } vpMouseButtonType; }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpPixelMeterConversion.h b/modules/core/include/visp3/core/vpPixelMeterConversion.h index 5531eb231e..4af6db7267 100644 --- a/modules/core/include/visp3/core/vpPixelMeterConversion.h +++ b/modules/core/include/visp3/core/vpPixelMeterConversion.h @@ -31,14 +31,14 @@ * Pixel to meter conversion. */ -#ifndef _vpPixelMeterConversion_h_ -#define _vpPixelMeterConversion_h_ - /*! \file vpPixelMeterConversion.h \brief pixel to meter conversion - */ + +#ifndef _vpPixelMeterConversion_h_ +#define _vpPixelMeterConversion_h_ + #include #include #include @@ -50,6 +50,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpPixelMeterConversion @@ -384,5 +388,7 @@ class VISP_EXPORT vpPixelMeterConversion //@} #endif }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpPlane.h b/modules/core/include/visp3/core/vpPlane.h index 7c150a641f..0f1abb167c 100644 --- a/modules/core/include/visp3/core/vpPlane.h +++ b/modules/core/include/visp3/core/vpPlane.h @@ -31,13 +31,17 @@ * Plane geometrical structure. */ -#ifndef vpPlane_hh -#define vpPlane_hh +#ifndef _vpPlane_h_ +#define _vpPlane_h_ #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpPlane @@ -155,5 +159,7 @@ class VISP_EXPORT vpPlane double getIntersection(const vpColVector &M1, vpColVector &H) const; void changeFrame(const vpHomogeneousMatrix &cMo); }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpPoint.h b/modules/core/include/visp3/core/vpPoint.h index b2f4f069b3..2453ee3734 100644 --- a/modules/core/include/visp3/core/vpPoint.h +++ b/modules/core/include/visp3/core/vpPoint.h @@ -31,20 +31,24 @@ * Point feature. */ -#ifndef vpPoint_H -#define vpPoint_H - /*! \file vpPoint.h \brief class that defines what is a point */ -class vpHomogeneousMatrix; +#ifndef _vpPoint_H_ +#define _vpPoint_H_ #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif +class vpHomogeneousMatrix; + /*! \class vpPoint \ingroup group_core_geometry @@ -148,5 +152,7 @@ class VISP_EXPORT vpPoint : public vpForwardProjection //! Basic construction. void init() vp_override; }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpPolygon.h b/modules/core/include/visp3/core/vpPolygon.h index c3652991e8..d9b055d9a3 100644 --- a/modules/core/include/visp3/core/vpPolygon.h +++ b/modules/core/include/visp3/core/vpPolygon.h @@ -45,6 +45,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpPolygon \ingroup group_core_geometry @@ -96,19 +100,6 @@ int main() */ class VISP_EXPORT vpPolygon { -protected: - //! Collection of image points containing the corners. - std::vector _corners; - //! Center of the polygon. It is automatically computed when the corners are - //! set. - vpImagePoint _center; - //! Area of the polygon. - double _area; - //! Flag set to true when the polygon is a good polygon (ie. it has more - //! than two corners) or false otherwise. - bool _goodPoly; - //! Bounding box containing the polygon. - vpRect _bbox; public: enum PointInPolygonMethod @@ -185,6 +176,20 @@ class VISP_EXPORT vpPolygon void updateCenter(); void updateBoundingBox(); +protected: + //! Collection of image points containing the corners. + std::vector _corners; + //! Center of the polygon. It is automatically computed when the corners are + //! set. + vpImagePoint _center; + //! Area of the polygon. + double _area; + //! Flag set to true when the polygon is a good polygon (ie. it has more + //! than two corners) or false otherwise. + bool _goodPoly; + //! Bounding box containing the polygon. + vpRect _bbox; + private: bool testIntersectionSegments(const vpImagePoint &ip1, const vpImagePoint &ip2, const vpImagePoint &ip3, const vpImagePoint &ip4) const; @@ -201,5 +206,7 @@ class VISP_EXPORT vpPolygon static bool isInside(const std::vector &roi, const double &i, const double &j, const PointInPolygonMethod &method = PnPolyRayCasting); }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpPoseVector.h b/modules/core/include/visp3/core/vpPoseVector.h index 170b81459d..fc601b3987 100644 --- a/modules/core/include/visp3/core/vpPoseVector.h +++ b/modules/core/include/visp3/core/vpPoseVector.h @@ -32,9 +32,6 @@ * a rotation vector (theta u representation) and t is a translation vector. */ -#ifndef vpPOSEVECTOR_H -#define vpPOSEVECTOR_H - /*! \file vpPoseVector.h @@ -43,11 +40,8 @@ translation vector. */ -class vpRotationMatrix; -class vpHomogeneousMatrix; -class vpTranslationVector; -class vpThetaUVector; -class vpRowVector; +#ifndef _vpPOSEVECTOR_H_ +#define _vpPOSEVECTOR_H_ #include #include @@ -55,10 +49,33 @@ class vpRowVector; #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +class vpPoseVector; +} +#endif + #ifdef VISP_HAVE_NLOHMANN_JSON #include +#if defined(ENABLE_VISP_NAMESPACE) +void to_json(nlohmann::json &j, const visp::vpPoseVector &pose); +void from_json(const nlohmann::json &j, visp::vpPoseVector &pose); +#endif #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif +class vpRotationMatrix; +class vpHomogeneousMatrix; +class vpTranslationVector; +class vpThetaUVector; +class vpRowVector; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif /*! \class vpPoseVector @@ -186,7 +203,11 @@ class vpRowVector; {"cols":1,"data":[0.1,0.2,0.3,3.141592653589793,1.5707963267948966,0.7853981633974483],"rows":6,"type":"vpPoseVector"} \endcode */ -class VISP_EXPORT vpPoseVector : public vpArray2D +class VISP_EXPORT +#if defined(ENABLE_VISP_NAMESPACE) + visp:: +#endif +vpPoseVector: public vpArray2D { public: // constructor @@ -303,8 +324,8 @@ class VISP_EXPORT vpPoseVector : public vpArray2D public: static const std::string jsonTypeName; private: - friend void to_json(nlohmann::json &j, const vpPoseVector &cam); - friend void from_json(const nlohmann::json &j, vpPoseVector &cam); + friend void ::to_json(nlohmann::json &j, const vpPoseVector &cam); + friend void ::from_json(const nlohmann::json &j, vpPoseVector &cam); // Conversion helper function to avoid circular dependencies and MSVC errors that are not exported in the DLL void parse_json(const nlohmann::json &j); void convert_to_json(nlohmann::json &j) const; @@ -327,11 +348,23 @@ class VISP_EXPORT vpPoseVector : public vpArray2D #ifdef VISP_HAVE_NLOHMANN_JSON #include -inline void to_json(nlohmann::json &j, const vpPoseVector &r) +inline void to_json(nlohmann::json &j, +#if defined(ENABLE_VISP_NAMESPACE) +const visp::vpPoseVector &r +#else +const vpPoseVector &r +#endif +) { r.convert_to_json(j); } -inline void from_json(const nlohmann::json &j, vpPoseVector &r) +inline void from_json(const nlohmann::json &j, +#if defined(ENABLE_VISP_NAMESPACE) +visp::vpPoseVector &r +#else +vpPoseVector &r +#endif +) { r.parse_json(j); } diff --git a/modules/core/include/visp3/core/vpQuaternionVector.h b/modules/core/include/visp3/core/vpQuaternionVector.h index 843656ed17..5a891f8d62 100644 --- a/modules/core/include/visp3/core/vpQuaternionVector.h +++ b/modules/core/include/visp3/core/vpQuaternionVector.h @@ -31,9 +31,6 @@ * Quaternion definition. */ -#ifndef _vpQuaternionVector_h_ -#define _vpQuaternionVector_h_ - /*! * \file vpQuaternionVector.h * @@ -41,11 +38,18 @@ * operations on it. */ +#ifndef _vpQuaternionVector_h_ +#define _vpQuaternionVector_h_ + #include #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpQuaternionVector @@ -103,9 +107,6 @@ */ class VISP_EXPORT vpQuaternionVector : public vpRotationVector { -private: - static const double minimum; - public: vpQuaternionVector(); vpQuaternionVector(const vpQuaternionVector &q); @@ -162,6 +163,12 @@ class VISP_EXPORT vpQuaternionVector : public vpRotationVector static vpQuaternionVector lerp(const vpQuaternionVector &q0, const vpQuaternionVector &q1, double t); static vpQuaternionVector nlerp(const vpQuaternionVector &q0, const vpQuaternionVector &q1, double t); static vpQuaternionVector slerp(const vpQuaternionVector &q0, const vpQuaternionVector &q1, double t); -}; +private: + static const double minimum; + +}; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpRGBa.h b/modules/core/include/visp3/core/vpRGBa.h index 772ba97f3a..aec295dbd1 100644 --- a/modules/core/include/visp3/core/vpRGBa.h +++ b/modules/core/include/visp3/core/vpRGBa.h @@ -31,17 +31,22 @@ * RGBA pixel. */ -#ifndef vpRGBa_h -#define vpRGBa_h - /*! \file vpRGBa.h \brief Define the object vpRGBa that is used to build color images (it defines a RGB 32 bits structure, fourth byte is not used) */ +#ifndef _vpRGBa_h_ +#define _vpRGBa_h_ + +#include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpRGBa @@ -141,5 +146,7 @@ class VISP_EXPORT vpRGBa friend VISP_EXPORT vpRGBa operator*(const double &x, const vpRGBa &rgb); }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpRGBf.h b/modules/core/include/visp3/core/vpRGBf.h index 828a59b087..099d956094 100644 --- a/modules/core/include/visp3/core/vpRGBf.h +++ b/modules/core/include/visp3/core/vpRGBf.h @@ -31,17 +31,22 @@ * 32-bit floating point RGB pixel. */ -#ifndef vpRGBf_h -#define vpRGBf_h - /*! \file vpRGBf.h \brief Define the object vpRGBf that is used to build color images (it defines a RGB 32-bit floating point structure) */ +#ifndef _vpRGBf_h_ +#define _vpRGBf_h_ + +#include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpRGBf @@ -127,5 +132,7 @@ class VISP_EXPORT vpRGBf friend VISP_EXPORT vpRGBf operator*(double x, const vpRGBf &rgb); }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpRansac.h b/modules/core/include/visp3/core/vpRansac.h index 2be17d461c..adfa6aaa20 100644 --- a/modules/core/include/visp3/core/vpRansac.h +++ b/modules/core/include/visp3/core/vpRansac.h @@ -35,15 +35,20 @@ \file vpRansac.h */ -#ifndef vpRANSAC_HH -#define vpRANSAC_HH +#ifndef _vpRANSAC_H_ +#define _vpRANSAC_H_ #include +#include #include #include // debug and trace #include #include // random number generation +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpRansac \ingroup group_core_robust @@ -241,5 +246,7 @@ bool vpRansac::ransac(unsigned int npts, const vpColVector &x, return true; } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpRect.h b/modules/core/include/visp3/core/vpRect.h index 207720d00e..ba1242e2c0 100644 --- a/modules/core/include/visp3/core/vpRect.h +++ b/modules/core/include/visp3/core/vpRect.h @@ -31,9 +31,20 @@ * Defines a rectangle in the plane. */ -#ifndef vpRect_h -#define vpRect_h +#ifndef _vpRect_h_ +#define _vpRect_h_ +#include +#include +#include +#include +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpRect \ingroup group_core_geometry @@ -65,13 +76,6 @@ setting sizes, e.g. setWidth(), setHeight() */ - -#include -#include -#include -#include -#include - class VISP_EXPORT vpRect { public: @@ -342,7 +346,7 @@ class VISP_EXPORT vpRect \sa setLeft() */ - inline void setRight(double pos) { this->width = pos - this->left + 1.0; } + inline void setRight(double pos) { this->width = (pos - this->left) + 1.0; } /*! Sets the top edge position of the rectangle to pos. May change the bottom @@ -408,5 +412,7 @@ class VISP_EXPORT vpRect double width; // Rectangle width double height; // Rectangle height }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpRectOriented.h b/modules/core/include/visp3/core/vpRectOriented.h index afe8667a66..b1fe5d323e 100644 --- a/modules/core/include/visp3/core/vpRectOriented.h +++ b/modules/core/include/visp3/core/vpRectOriented.h @@ -31,18 +31,22 @@ * Defines a (possibly oriented) rectangle in the plane. */ -#ifndef vpRectOriented_h -#define vpRectOriented_h +#ifndef _vpRectOriented_h_ +#define _vpRectOriented_h_ +#include +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpRectOriented * \ingroup group_core_geometry * \brief Defines an oriented rectangle in the plane. */ - -#include -#include - class VISP_EXPORT vpRectOriented { public: @@ -105,4 +109,7 @@ class VISP_EXPORT vpRectOriented vpImagePoint m_bottomRight; bool isLeft(const vpImagePoint &pointToTest, const vpImagePoint &point1, const vpImagePoint &point2) const; }; -#endif // vpRectOriented_h +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif +#endif // _vpRectOriented_h_ diff --git a/modules/core/include/visp3/core/vpRobust.h b/modules/core/include/visp3/core/vpRobust.h index 5c52ef4e89..fa3282aef5 100644 --- a/modules/core/include/visp3/core/vpRobust.h +++ b/modules/core/include/visp3/core/vpRobust.h @@ -42,6 +42,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpRobust \ingroup group_core_robust @@ -90,27 +94,6 @@ class VISP_EXPORT vpRobust HUBER //!< Huber influence function. } vpRobustEstimatorType; -private: - //! Normalized residue - vpColVector m_normres; - //! Sorted normalized Residues - vpColVector m_sorted_normres; - //! Sorted residues - vpColVector m_sorted_residues; - - //! Min admissible value of residual vector Median Absolute Deviation - double m_mad_min; - //! Previous value of residual vector Median Absolute Deviation - double m_mad_prev; -#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) - //! Iteration, only used in deprecated simultMEstimator() - unsigned int m_iter; -#endif - //! Size of the containers - unsigned int m_size; - //! Residual vector Median Absolute Deviation - double m_mad; - public: vpRobust(); vpRobust(const vpRobust &other); @@ -181,6 +164,27 @@ class VISP_EXPORT vpRobust vp_deprecated vpColVector simultMEstimator(vpColVector &residues); //@} #endif +private: + //! Normalized residue + vpColVector m_normres; + //! Sorted normalized Residues + vpColVector m_sorted_normres; + //! Sorted residues + vpColVector m_sorted_residues; + + //! Min admissible value of residual vector Median Absolute Deviation + double m_mad_min; + //! Previous value of residual vector Median Absolute Deviation + double m_mad_prev; +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) + //! Iteration, only used in deprecated simultMEstimator() + unsigned int m_iter; +#endif + //! Size of the containers + unsigned int m_size; + //! Residual vector Median Absolute Deviation + double m_mad; + private: //! Resize containers for sort methods void resize(unsigned int n_data); @@ -244,5 +248,7 @@ class VISP_EXPORT vpRobust double select(vpColVector &a, int l, int r, int k); //@} }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpRotationMatrix.h b/modules/core/include/visp3/core/vpRotationMatrix.h index 81fa71b15a..c7c4ca60b9 100644 --- a/modules/core/include/visp3/core/vpRotationMatrix.h +++ b/modules/core/include/visp3/core/vpRotationMatrix.h @@ -31,14 +31,14 @@ * Rotation matrix. */ -#ifndef _vpRotationMatrix_h_ -#define _vpRotationMatrix_h_ - /*! \file vpRotationMatrix.h \brief Class that consider the particular case of rotation matrix */ +#ifndef _vpRotationMatrix_h_ +#define _vpRotationMatrix_h_ + #include #include #include @@ -50,6 +50,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpRotationMatrix @@ -231,5 +235,7 @@ class VISP_EXPORT vpRotationMatrix : public vpArray2D VISP_EXPORT #endif vpRotationMatrix operator*(const double &x, const vpRotationMatrix &R); - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpRotationVector.h b/modules/core/include/visp3/core/vpRotationVector.h index ac49de5431..b05d2e3e6d 100644 --- a/modules/core/include/visp3/core/vpRotationVector.h +++ b/modules/core/include/visp3/core/vpRotationVector.h @@ -31,20 +31,26 @@ * Generic rotation vector (cannot be used as is !). */ -#ifndef _vpRotationVector_h_ -#define _vpRotationVector_h_ - /*! \file vpRotationVector.h \brief class that consider the case of a generic rotation vector (cannot be used as is !) */ +#ifndef _vpRotationVector_h_ +#define _vpRotationVector_h_ + #include #include #include #include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif class vpRowVector; class vpColVector; @@ -157,4 +163,7 @@ VISP_EXPORT #endif vpColVector operator*(const double &x, const 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 3119f303da..9b9ac3060f 100644 --- a/modules/core/include/visp3/core/vpRowVector.h +++ b/modules/core/include/visp3/core/vpRowVector.h @@ -31,16 +31,22 @@ * Operation on row vectors. */ -#ifndef vpRowVector_H -#define vpRowVector_H +#ifndef _vpRowVector_H_ +#define _vpRowVector_H_ #include +#include #include #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + class vpMatrix; class vpColVector; @@ -335,5 +341,7 @@ class VISP_EXPORT vpRowVector : public vpArray2D }; VISP_EXPORT vpRowVector operator*(const double &x, const vpRowVector &v); - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpRxyzVector.h b/modules/core/include/visp3/core/vpRxyzVector.h index 64a957b833..7e0598c82f 100644 --- a/modules/core/include/visp3/core/vpRxyzVector.h +++ b/modules/core/include/visp3/core/vpRxyzVector.h @@ -32,9 +32,6 @@ * Rxyz(phi,theta,psi) = Rot(x,phi)Rot(y,theta)Rot(z,psi). */ -#ifndef _vpRxyzVector_h_ -#define _vpRxyzVector_h_ - /*! \file vpRxyzVector.h @@ -44,10 +41,18 @@ Rxyz(phi,theta,psi) = Rot(x,phi)Rot(y,theta)Rot(z,psi) */ +#ifndef _vpRxyzVector_h_ +#define _vpRxyzVector_h_ + #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + class vpRotationVector; class vpRotationMatrix; class vpThetaUVector; @@ -216,5 +221,7 @@ class VISP_EXPORT vpRxyzVector : public vpRotationVector vpRxyzVector &operator=(const std::initializer_list &list); #endif }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpRzyxVector.h b/modules/core/include/visp3/core/vpRzyxVector.h index 0ed07dc55b..977a236cff 100644 --- a/modules/core/include/visp3/core/vpRzyxVector.h +++ b/modules/core/include/visp3/core/vpRzyxVector.h @@ -32,9 +32,6 @@ * Rzyx(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(x,psi) */ -#ifndef _vpRzyxVector_h_ -#define _vpRzyxVector_h_ - /*! \file vpRzyxVector.h @@ -44,13 +41,21 @@ Rzyx(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(x,psi) */ -class vpRotationMatrix; -class vpThetaUVector; +#ifndef _vpRzyxVector_h_ +#define _vpRzyxVector_h_ #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + +class vpRotationMatrix; +class vpThetaUVector; + /*! \class vpRzyxVector @@ -217,5 +222,7 @@ class VISP_EXPORT vpRzyxVector : public vpRotationVector vpRzyxVector &operator=(const std::initializer_list &list); #endif }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpRzyzVector.h b/modules/core/include/visp3/core/vpRzyzVector.h index ae50e1f228..c5cf2b9b4a 100644 --- a/modules/core/include/visp3/core/vpRzyzVector.h +++ b/modules/core/include/visp3/core/vpRzyzVector.h @@ -32,9 +32,6 @@ * Rzyz(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(z,psi) */ -#ifndef _vpRzyzVector_h_ -#define _vpRzyzVector_h_ - /*! \file vpRzyzVector.h \brief class that consider the case of the Rzyz angles parameterization @@ -43,13 +40,21 @@ Rzyz(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(z,psi) */ -class vpRotationMatrix; -class vpThetaUVector; +#ifndef _vpRzyzVector_h_ +#define _vpRzyzVector_h_ #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + +class vpRotationMatrix; +class vpThetaUVector; + /*! \class vpRzyzVector @@ -216,4 +221,7 @@ class VISP_EXPORT vpRzyzVector : public vpRotationVector vpRzyzVector &operator=(const std::initializer_list &list); #endif }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpSphere.h b/modules/core/include/visp3/core/vpSphere.h index d28a723cab..bee076c35b 100644 --- a/modules/core/include/visp3/core/vpSphere.h +++ b/modules/core/include/visp3/core/vpSphere.h @@ -36,15 +36,21 @@ * \brief forward projection of a sphere */ -#ifndef vpSphere_hh -#define vpSphere_hh +#ifndef _vpSphere_h_ +#define _vpSphere_h_ +#include #include #include #include #include #include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpSphere * \ingroup group_core_geometry @@ -115,9 +121,6 @@ class VISP_EXPORT vpSphere : public vpForwardProjection void setWorldCoordinates(double oX, double oY, double oZ, double R); -protected: - void init() vp_override; - public: #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) /*! @@ -147,6 +150,11 @@ class VISP_EXPORT vpSphere : public vpForwardProjection vp_deprecated double get_mu02() const { return p[4]; } //@} #endif -}; +protected: + void init() vp_override; +}; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpSubColVector.h b/modules/core/include/visp3/core/vpSubColVector.h index ebfe81edc0..b78710511a 100644 --- a/modules/core/include/visp3/core/vpSubColVector.h +++ b/modules/core/include/visp3/core/vpSubColVector.h @@ -31,17 +31,22 @@ * Mask on a vpColVector. */ -#ifndef _vpSubColVector_h_ -#define _vpSubColVector_h_ - -#include - /*! * \file vpSubColVector.h * * \brief Definition of the vpSubColVector class */ +#ifndef _vpSubColVector_h_ +#define _vpSubColVector_h_ + +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpSubColVector * \ingroup group_core_matrices @@ -54,16 +59,6 @@ */ class VISP_EXPORT vpSubColVector : public vpColVector { -private: - //! Copy constructor unavailable - vpSubColVector(const vpSubColVector &v /* m */); - -protected: - //! Number of row of parent vpColVector at initialization - unsigned int m_pRowNum; - //! Parent vpColVector - vpColVector *m_parent; - public: vpSubColVector(); vpSubColVector(vpColVector &v, const unsigned int &offset, const unsigned int &nrows); @@ -82,6 +77,20 @@ class VISP_EXPORT vpSubColVector : public vpColVector vpSubColVector &operator=(const vpColVector &B); vpSubColVector &operator=(const vpMatrix &B); vpSubColVector &operator=(const double &x); -}; +protected: + //! Number of row of parent vpColVector at initialization + unsigned int m_pRowNum; + //! Parent vpColVector + vpColVector *m_parent; + +private: + //! Copy constructor unavailable + vpSubColVector(const vpSubColVector &v /* m */); + + +}; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpSubMatrix.h b/modules/core/include/visp3/core/vpSubMatrix.h index 8959603ba1..12237b21d5 100644 --- a/modules/core/include/visp3/core/vpSubMatrix.h +++ b/modules/core/include/visp3/core/vpSubMatrix.h @@ -31,17 +31,22 @@ * Mask on a vpMatrix. */ -#ifndef _vpSubMatrix_h_ -#define _vpSubMatrix_h_ - -#include - /*! * \file vpSubMatrix.h * * \brief Definition of the vpSubMatrix class */ +#ifndef _vpSubMatrix_h_ +#define _vpSubMatrix_h_ + +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpSubMatrix * \ingroup group_core_matrices @@ -53,18 +58,6 @@ */ class VISP_EXPORT vpSubMatrix : public vpMatrix { -private: - //! Eye method unavailable - void eye(unsigned int n); - //! Eye method unavailable - void eye(unsigned int m, unsigned int n); - //! Copy constructor unavailable - vpSubMatrix(const vpSubMatrix &m /* m */); - -protected: - unsigned int pRowNum; - unsigned int pColNum; - vpMatrix *parent; public: //! Default constructor @@ -88,6 +81,21 @@ class VISP_EXPORT vpSubMatrix : public vpMatrix vpSubMatrix &operator=(const vpMatrix &B); //! Operation such as subA = x vpSubMatrix &operator=(const double &x); -}; +protected: + unsigned int pRowNum; + unsigned int pColNum; + vpMatrix *parent; + +private: + //! Eye method unavailable + void eye(unsigned int n); + //! Eye method unavailable + void eye(unsigned int m, unsigned int n); + //! Copy constructor unavailable + vpSubMatrix(const vpSubMatrix &m /* m */); +}; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpSubRowVector.h b/modules/core/include/visp3/core/vpSubRowVector.h index ffd5e1b0c1..ba6be0fe83 100644 --- a/modules/core/include/visp3/core/vpSubRowVector.h +++ b/modules/core/include/visp3/core/vpSubRowVector.h @@ -31,17 +31,22 @@ * Mask on a vpRowVector. */ -#ifndef _vpSubRowVector_h_ -#define _vpSubRowVector_h_ - -#include - /*! * \file vpSubRowVector.h * * \brief Definition of the vpSubRowVector class */ +#ifndef _vpSubRowVector_h_ +#define _vpSubRowVector_h_ + +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpSubRowVector * \ingroup group_core_matrices @@ -54,15 +59,6 @@ */ class VISP_EXPORT vpSubRowVector : public vpRowVector { -private: - //! Copy constructor unavailable - vpSubRowVector(const vpSubRowVector &m /* m */); - -protected: - //! Number of row of parent vpColVector at initialization - unsigned int m_pColNum; - //! Parent vpColVector - vpRowVector *m_parent; public: vpSubRowVector(); @@ -77,6 +73,18 @@ class VISP_EXPORT vpSubRowVector : public vpRowVector vpSubRowVector &operator=(const vpRowVector &B); vpSubRowVector &operator=(const vpMatrix &B); vpSubRowVector &operator=(const double &x); -}; +protected: + //! Number of row of parent vpColVector at initialization + unsigned int m_pColNum; + //! Parent vpColVector + vpRowVector *m_parent; + +private: + //! Copy constructor unavailable + vpSubRowVector(const vpSubRowVector &m /* m */); +}; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpThetaUVector.h b/modules/core/include/visp3/core/vpThetaUVector.h index 21bd520383..5990620aa7 100644 --- a/modules/core/include/visp3/core/vpThetaUVector.h +++ b/modules/core/include/visp3/core/vpThetaUVector.h @@ -31,15 +31,28 @@ * Theta U parameterization for the rotation. */ -#ifndef _vpThetaUVector_h_ -#define _vpThetaUVector_h_ - /*! \file vpThetaUVector.h \brief class that consider the case of the Theta U parameterization for the rotation */ +#ifndef _vpThetaUVector_h_ +#define _vpThetaUVector_h_ + +#include +#include +#include +#include +#include +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + class vpHomogeneousMatrix; class vpRotationMatrix; class vpPoseVector; @@ -50,15 +63,6 @@ class vpColVector; class vpRotationVector; class vpQuaternionVector; -#include -#include -#include -#include -#include -#include -#include -#include - /*! \class vpThetaUVector @@ -165,9 +169,6 @@ class vpQuaternionVector; */ class VISP_EXPORT vpThetaUVector : public vpRotationVector { -private: - static const double minimum; - public: vpThetaUVector(); vpThetaUVector(const vpThetaUVector &tu); @@ -239,6 +240,12 @@ class VISP_EXPORT vpThetaUVector : public vpRotationVector #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) vpThetaUVector &operator=(const std::initializer_list &list); #endif -}; +private: + static const double minimum; + +}; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpTime.h b/modules/core/include/visp3/core/vpTime.h index 78a3649b7f..3e348cccf5 100644 --- a/modules/core/include/visp3/core/vpTime.h +++ b/modules/core/include/visp3/core/vpTime.h @@ -31,13 +31,14 @@ * Time management and measurement. */ -#ifndef vpTime_h -#define vpTime_h - /*! \file vpTime.h \brief Time management and measurement */ + +#ifndef _vpTime_h_ +#define _vpTime_h_ + #include #include #include @@ -47,6 +48,10 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \ingroup group_core_time * \brief Time management and measurement. @@ -99,5 +104,7 @@ class VISP_EXPORT vpChrono double m_lastTimePoint; #endif }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpTracker.h b/modules/core/include/visp3/core/vpTracker.h index 0d0d6bd860..baaeeba60b 100644 --- a/modules/core/include/visp3/core/vpTracker.h +++ b/modules/core/include/visp3/core/vpTracker.h @@ -31,18 +31,23 @@ * Generic tracker. */ -#ifndef vpTracker_H -#define vpTracker_H - /*! * \file vpTracker.h * \brief Class that defines what is a generic tracker. */ +#ifndef _vpTracker_H_ +#define _vpTracker_H_ + +#include #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpTracker * \ingroup group_core_trackers @@ -83,7 +88,7 @@ class VISP_EXPORT vpTracker //! Copy constructor. vpTracker(const vpTracker &tracker); //! Destructor. - virtual ~vpTracker() { ; } + virtual ~vpTracker() { } /** @name Public Member Functions Inherited from vpTracker */ //@{ @@ -103,5 +108,7 @@ class VISP_EXPORT vpTracker void init(); //@} }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpTrackingException.h b/modules/core/include/visp3/core/vpTrackingException.h index c17e6bcd9a..761169a5b3 100644 --- a/modules/core/include/visp3/core/vpTrackingException.h +++ b/modules/core/include/visp3/core/vpTrackingException.h @@ -31,18 +31,24 @@ * Exceptions that can be emitted by the vpTracking class and its derivatives. */ -#ifndef _vpTrackingException_H -#define _vpTrackingException_H - /*! * \file vpTrackingException.h * \brief error that can be emitted by the vpTracker class and its derivatives */ +#ifndef _vpTrackingException_H_ +#define _vpTrackingException_H_ + #include #include +#include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpTrackingException * \ingroup group_core_debug @@ -87,5 +93,7 @@ class VISP_EXPORT vpTrackingException : public vpException */ explicit vpTrackingException(int id) : vpException(id) { } }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpTranslationVector.h b/modules/core/include/visp3/core/vpTranslationVector.h index 48e1a3b440..4481c10c2f 100644 --- a/modules/core/include/visp3/core/vpTranslationVector.h +++ b/modules/core/include/visp3/core/vpTranslationVector.h @@ -31,20 +31,25 @@ * Translation vector. */ -#ifndef vpTRANSLATIONVECTOR_H -#define vpTRANSLATIONVECTOR_H - /*! * \file vpTranslationVector.h * \brief Class that consider the case of a translation vector. */ +#ifndef _vpTRANSLATIONVECTOR_H_ +#define _vpTRANSLATIONVECTOR_H_ + #include #include #include -#include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif +class vpMatrix; + /*! \class vpTranslationVector @@ -207,5 +212,7 @@ class VISP_EXPORT vpTranslationVector : public vpArray2D protected: unsigned int m_index; // index used for operator<< and operator, to fill a vector }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpUniRand.h b/modules/core/include/visp3/core/vpUniRand.h index b57614149f..bec507bf08 100644 --- a/modules/core/include/visp3/core/vpUniRand.h +++ b/modules/core/include/visp3/core/vpUniRand.h @@ -82,6 +82,11 @@ typedef unsigned __int32 uint32_t; #endif #include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpUniRand @@ -121,19 +126,6 @@ typedef unsigned __int32 uint32_t; */ class VISP_EXPORT vpUniRand { -private: - struct vpPcgStateSetseq_64_t - { // Internals are *Private*. - uint64_t state; // RNG state. All values are possible. - uint64_t inc; // Controls which RNG sequence (stream) is - // selected. Must *always* be odd. - - vpPcgStateSetseq_64_t(uint64_t state_ = 0x853c49e6748fea9bULL, uint64_t inc_ = 0xda3e39cb94b95bdbULL) - : state(state_), inc(inc_) - { } - }; - typedef struct vpPcgStateSetseq_64_t pcg32_random_t; - public: vpUniRand(); vpUniRand(uint64_t seed, uint64_t seq = 0x123465789ULL); @@ -165,6 +157,19 @@ class VISP_EXPORT vpUniRand return shuffled; } +private: + struct vpPcgStateSetseq_64_t + { // Internals are *Private*. + uint64_t state; // RNG state. All values are possible. + uint64_t inc; // Controls which RNG sequence (stream) is + // selected. Must *always* be odd. + + vpPcgStateSetseq_64_t(uint64_t state_ = 0x853c49e6748fea9bULL, uint64_t inc_ = 0xda3e39cb94b95bdbULL) + : state(state_), inc(inc_) + { } + }; + typedef struct vpPcgStateSetseq_64_t pcg32_random_t; + private: uint32_t boundedRand(uint32_t bound); @@ -172,5 +177,7 @@ class VISP_EXPORT vpUniRand float m_maxInvFlt; pcg32_random_t m_rng; }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpVelocityTwistMatrix.h b/modules/core/include/visp3/core/vpVelocityTwistMatrix.h index 8e954cf2fa..2a97a8525b 100644 --- a/modules/core/include/visp3/core/vpVelocityTwistMatrix.h +++ b/modules/core/include/visp3/core/vpVelocityTwistMatrix.h @@ -31,18 +31,22 @@ * Velocity twist transformation matrix. */ -#ifndef vpVelocityTwistMatrix_h -#define vpVelocityTwistMatrix_h +#ifndef _vpVelocityTwistMatrix_h_ +#define _vpVelocityTwistMatrix_h_ #include #include #include #include -#include #include -class vpHomogeneousMatrix; +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif class vpColVector; +class vpHomogeneousMatrix; +class vpMatrix; /*! \class vpVelocityTwistMatrix @@ -239,5 +243,7 @@ class VISP_EXPORT vpVelocityTwistMatrix : public vpArray2D //@} #endif }; - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/include/visp3/core/vpXmlParserCamera.h b/modules/core/include/visp3/core/vpXmlParserCamera.h index ebfb896dca..aa42d82b42 100644 --- a/modules/core/include/visp3/core/vpXmlParserCamera.h +++ b/modules/core/include/visp3/core/vpXmlParserCamera.h @@ -38,14 +38,18 @@ */ -#ifndef vpXMLPARSERCAMERA_H -#define vpXMLPARSERCAMERA_H +#ifndef _vpXMLPARSERCAMERA_H_ +#define _vpXMLPARSERCAMERA_H_ #include #if defined(VISP_HAVE_PUGIXML) #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpXmlParserCamera @@ -198,5 +202,8 @@ class VISP_EXPORT vpXmlParserCamera class Impl; Impl *m_impl; }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif diff --git a/modules/core/include/visp3/core/vpXmlParserHomogeneousMatrix.h b/modules/core/include/visp3/core/vpXmlParserHomogeneousMatrix.h index b99d65609b..eb440b024f 100644 --- a/modules/core/include/visp3/core/vpXmlParserHomogeneousMatrix.h +++ b/modules/core/include/visp3/core/vpXmlParserHomogeneousMatrix.h @@ -39,14 +39,18 @@ */ -#ifndef VP_XMLPARSERHOMOGENEOUSMATRIX_H -#define VP_XMLPARSERHOMOGENEOUSMATRIX_H +#ifndef _VP_XMLPARSERHOMOGENEOUSMATRIX_H_ +#define _VP_XMLPARSERHOMOGENEOUSMATRIX_H_ #include #if defined(VISP_HAVE_PUGIXML) #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpXmlParserHomogeneousMatrix @@ -171,5 +175,8 @@ class VISP_EXPORT vpXmlParserHomogeneousMatrix class Impl; Impl *m_impl; }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif diff --git a/modules/core/include/visp3/core/vpXmlParserRectOriented.h b/modules/core/include/visp3/core/vpXmlParserRectOriented.h index 861546c013..329dc63fe7 100644 --- a/modules/core/include/visp3/core/vpXmlParserRectOriented.h +++ b/modules/core/include/visp3/core/vpXmlParserRectOriented.h @@ -37,14 +37,18 @@ Class vpXmlParserRectOriented allows to load and save oriented rectangles in a file XML */ -#ifndef vpXmlParserRectOriented_h -#define vpXmlParserRectOriented_h +#ifndef _vpXmlParserRectOriented_h_ +#define _vpXmlParserRectOriented_h_ #include #if defined(VISP_HAVE_PUGIXML) #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \class vpXmlParserRectOriented @@ -108,5 +112,8 @@ class VISP_EXPORT vpXmlParserRectOriented class Impl; Impl *m_impl; }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif // vpXmlParserRectOriented_h diff --git a/modules/core/src/camera/vpCameraParameters.cpp b/modules/core/src/camera/vpCameraParameters.cpp index 4b5d19b817..465b6dddd1 100644 --- a/modules/core/src/camera/vpCameraParameters.cpp +++ b/modules/core/src/camera/vpCameraParameters.cpp @@ -48,6 +48,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + const double vpCameraParameters::DEFAULT_PX_PARAMETER = 600.0; const double vpCameraParameters::DEFAULT_PY_PARAMETER = 600.0; const double vpCameraParameters::DEFAULT_U0_PARAMETER = 192.0; @@ -683,3 +688,7 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpCameraParameters } return os; } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/camera/vpColorDepthConversion.cpp b/modules/core/src/camera/vpColorDepthConversion.cpp index f45bb1ed6c..b84a4360a9 100644 --- a/modules/core/src/camera/vpColorDepthConversion.cpp +++ b/modules/core/src/camera/vpColorDepthConversion.cpp @@ -46,6 +46,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif namespace { @@ -252,3 +256,6 @@ vpImagePoint vpColorDepthConversion::projectColorToDepth( #endif return depth_pixel; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/camera/vpMeterPixelConversion.cpp b/modules/core/src/camera/vpMeterPixelConversion.cpp index 05a3b8386d..840e02b198 100644 --- a/modules/core/src/camera/vpMeterPixelConversion.cpp +++ b/modules/core/src/camera/vpMeterPixelConversion.cpp @@ -44,6 +44,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Line parameters conversion from normalized coordinates \f$(\rho_m,\theta_m)\f$ expressed in the image plane to pixel coordinates \f$(\rho_p,\theta_p)\f$ using ViSP camera parameters. This function doesn't use distortion @@ -402,3 +406,6 @@ void vpMeterPixelConversion::convertPoint(const cv::Mat &cameraMatrix, const cv: iP.set_v(imagePoints_vec[0].y); } #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/camera/vpPixelMeterConversion.cpp b/modules/core/src/camera/vpPixelMeterConversion.cpp index a116ca6651..0c4fcf9184 100644 --- a/modules/core/src/camera/vpPixelMeterConversion.cpp +++ b/modules/core/src/camera/vpPixelMeterConversion.cpp @@ -43,6 +43,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * Convert ellipse parameters (ie ellipse center and normalized centered moments) * from pixels \f$(u_c, v_c, n_{{20}_p}, n_{{11}_p}, n_{{02}_p})\f$ @@ -336,3 +340,6 @@ void vpPixelMeterConversion::convertPoint(const cv::Mat &cameraMatrix, const cv: } #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/camera/vpXmlParserCamera.cpp b/modules/core/src/camera/vpXmlParserCamera.cpp index 42200c9530..2465884265 100644 --- a/modules/core/src/camera/vpXmlParserCamera.cpp +++ b/modules/core/src/camera/vpXmlParserCamera.cpp @@ -81,6 +81,10 @@ #define LABEL_XML_ADDITIONAL_INFO "additional_information" +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpXmlParserCamera::Impl { @@ -1227,7 +1231,9 @@ void vpXmlParserCamera::setSubsampling_width(unsigned int subsampling) { m_impl- void vpXmlParserCamera::setSubsampling_height(unsigned int subsampling) { m_impl->setSubsampling_height(subsampling); } void vpXmlParserCamera::setWidth(unsigned int width) { m_impl->setWidth(width); } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpXmlParserCamera.cpp.o) has no symbols void dummy_vpXmlParserCamera() { }; diff --git a/modules/core/src/display/vpColor.cpp b/modules/core/src/display/vpColor.cpp index 0af91b46ff..cfeff37f8b 100644 --- a/modules/core/src/display/vpColor.cpp +++ b/modules/core/src/display/vpColor.cpp @@ -35,6 +35,10 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif // FS: Sould be improved to avoid the #if preprocessor line. Not a good idea // to define colors in static. // See also vpColor.h where things need to be improved. @@ -98,7 +102,7 @@ vpColor const vpColor::none = vpColor(0, 0, 0, id_unknown); const unsigned int vpColor::nbColors = 18; /*!< Array of available colors. */ -vpColor const vpColor::allColors[vpColor::nbColors] = {vpColor::blue, // 12 +vpColor const vpColor::allColors[vpColor::nbColors] = { vpColor::blue, // 12 vpColor::green, // 9 vpColor::red, // 6 vpColor::cyan, // 15 @@ -115,10 +119,10 @@ vpColor const vpColor::allColors[vpColor::nbColors] = {vpColor::blue, // 1 vpColor::gray, // 3 vpColor::darkGray, // 4 vpColor::black, // 0 - vpColor::white}; // 17 + vpColor::white }; // 17 #endif -vpColor colors[6] = {vpColor::blue, vpColor::green, vpColor::red, vpColor::cyan, vpColor::orange, vpColor::purple}; +vpColor colors[6] = { vpColor::blue, vpColor::green, vpColor::red, vpColor::cyan, vpColor::orange, vpColor::purple }; /*! Compare two colors. @@ -144,3 +148,6 @@ 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/display/vpDisplay.cpp b/modules/core/src/display/vpDisplay.cpp index 7b430151a3..c727dade04 100644 --- a/modules/core/src/display/vpDisplay.cpp +++ b/modules/core/src/display/vpDisplay.cpp @@ -33,6 +33,11 @@ * *****************************************************************************/ +/*! + \file vpDisplay.cpp + \brief Generic class for image display. +*/ + #include #include @@ -43,11 +48,10 @@ #include #include -/*! - \file vpDisplay.cpp - \brief Generic class for image display. -*/ - +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Default constructor. */ @@ -326,5 +330,8 @@ void vpDisplay::setDownScalingFactor(vpScaleType scaleType) { if (!m_displayHasBeenInitialized) { m_scaleType = scaleType; - } } +} +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/display/vpDisplay_impl.h b/modules/core/src/display/vpDisplay_impl.h index 253027b7ac..05f4331e34 100644 --- a/modules/core/src/display/vpDisplay_impl.h +++ b/modules/core/src/display/vpDisplay_impl.h @@ -37,6 +37,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif template void vp_display_close(vpImage &I) { if (I.display != nullptr) { @@ -724,3 +728,6 @@ template unsigned int vp_display_get_down_scaling_factor(const vpIm return 1; } } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/display/vpDisplay_rgba.cpp b/modules/core/src/display/vpDisplay_rgba.cpp index 2a3a069823..0e363fd2dd 100644 --- a/modules/core/src/display/vpDisplay_rgba.cpp +++ b/modules/core/src/display/vpDisplay_rgba.cpp @@ -41,7 +41,10 @@ // Modifications done in this file should be reported in all vpDisplay_*.cpp // files that implement other types (unsigned char, vpRGB, vpRGBa) //************************************************************************ - +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Close the display attached to I. */ @@ -1326,3 +1329,6 @@ void vpDisplay::setWindowPosition(const vpImage &I, int winx, int winy) \param I : Image associated to the display window. */ unsigned int vpDisplay::getDownScalingFactor(const vpImage &I) { return vp_display_get_down_scaling_factor(I); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/display/vpDisplay_uchar.cpp b/modules/core/src/display/vpDisplay_uchar.cpp index 6080fa4025..74a10f8e63 100644 --- a/modules/core/src/display/vpDisplay_uchar.cpp +++ b/modules/core/src/display/vpDisplay_uchar.cpp @@ -41,7 +41,10 @@ // Modifications done in this file should be reported in all vpDisplay_*.cpp // files that implement other types (unsigned char, vpRGB, vpRGBa) //************************************************************************ - +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Close the display attached to I. */ @@ -1336,3 +1339,6 @@ unsigned int vpDisplay::getDownScalingFactor(const vpImage &I) { return vp_display_get_down_scaling_factor(I); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/display/vpFeatureDisplay.cpp b/modules/core/src/display/vpFeatureDisplay.cpp index a764d6c8bb..2f083a14ea 100644 --- a/modules/core/src/display/vpFeatureDisplay.cpp +++ b/modules/core/src/display/vpFeatureDisplay.cpp @@ -49,6 +49,10 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Display a 2D point with coordinates (x, y) expressed in the image plane. These coordinates are obtained after perspective projection of the point. @@ -273,3 +277,6 @@ void vpFeatureDisplay::displayEllipse(double x, double y, double n20, double n11 vpMeterPixelConversion::convertEllipse(cam, circle, center, n20_p, n11_p, n02_p); vpDisplay::displayEllipse(I, center, n20_p, n11_p, n02_p, true, color, thickness); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/framegrabber/vpFrameGrabber.cpp b/modules/core/src/framegrabber/vpFrameGrabber.cpp index 2514ea5648..5740f5dd7b 100644 --- a/modules/core/src/framegrabber/vpFrameGrabber.cpp +++ b/modules/core/src/framegrabber/vpFrameGrabber.cpp @@ -34,6 +34,10 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif unsigned int vpFrameGrabber::getHeight() const { return height; @@ -43,3 +47,6 @@ unsigned int vpFrameGrabber::getWidth() const { return width; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/image/private/vpImageConvert_impl.h b/modules/core/src/image/private/vpImageConvert_impl.h index da34f3f0a8..177e8061f3 100644 --- a/modules/core/src/image/private/vpImageConvert_impl.h +++ b/modules/core/src/image/private/vpImageConvert_impl.h @@ -38,17 +38,22 @@ \brief Image conversion tools */ -#ifndef vpIMAGECONVERT_impl_H -#define vpIMAGECONVERT_impl_H +#ifndef _vpIMAGECONVERT_impl_H_ +#define _vpIMAGECONVERT_impl_H_ #if defined(VISP_HAVE_OPENMP) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) #include #include #endif +#include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Convert the input float depth image to a 8-bits depth image. The input depth value is assigned a value proportional to its frequency. @@ -60,6 +65,9 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage(src_depth.getSize()); + #if defined(VISP_HAVE_OPENMP) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) int nThreads = omp_get_max_threads(); std::vector > histograms(nThreads); @@ -68,7 +76,8 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage(src_depth.getSize()); ++i) { + + for (int i = 0; i < src_depth_size; ++i) { if (!vpMath::isNaN(src_depth.bitmap[i])) { ++(histograms[omp_get_thread_num()][static_cast(src_depth.bitmap[i])]); } @@ -81,26 +90,26 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage(src_depth.getSize()); ++i) { + for (int i = 0; i < src_depth_size; ++i) { if (!vpMath::isNaN(src_depth.bitmap[i])) { ++histogram[static_cast(src_depth.bitmap[i])]; } } #endif - for (int i = 2; i < 0x10000; ++i) + for (int i = 2; i < 0x10000; ++i) { histogram[i] += histogram[i - 1]; // Build a cumulative histogram for the indices in [1,0xFFFF] - + } dest_depth.resize(src_depth.getHeight(), src_depth.getWidth()); #ifdef VISP_HAVE_OPENMP #pragma omp parallel for #endif - for (int i = 0; i < static_cast(src_depth.getSize()); ++i) { + for (int i = 0; i < src_depth_size; ++i) { uint16_t d = static_cast(src_depth.bitmap[i]); if (d) { unsigned char f = - static_cast(histogram[d] * 255 / histogram[0xFFFF]); // 0-255 based on histogram location + static_cast((histogram[d] * 255) / histogram[0xFFFF]); // 0-255 based on histogram location dest_depth.bitmap[i] = f; } else { @@ -119,6 +128,7 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage(src_depth.getSize()); #if defined(VISP_HAVE_OPENMP) && (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11) int nThreads = omp_get_max_threads(); @@ -128,7 +138,7 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage(src_depth.getSize()); ++i) { + for (int i = 0; i < src_depth_size; ++i) { ++(histograms[omp_get_thread_num()][static_cast(src_depth.bitmap[i])]); } @@ -144,19 +154,20 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage(src_depth.getSize()); ++i) { + + for (int i = 0; i < src_depth_size; ++i) { uint16_t d = src_depth.bitmap[i]; if (d) { unsigned char f = - static_cast(histogram[d] * 255 / histogram[0xFFFF]); // 0-255 based on histogram location + static_cast((histogram[d] * 255) / histogram[0xFFFF]); // 0-255 based on histogram location dest_depth.bitmap[i] = f; } else { @@ -176,26 +187,27 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage &d dest_depth.resize(src_depth.getHeight(), src_depth.getWidth()); uint32_t histogram[0x10000]; memset(histogram, 0, sizeof(histogram)); + int src_depth_size = static_cast(src_depth.getSize()); #ifdef VISP_HAVE_OPENMP #pragma omp parallel for #endif - for (int i = 0; i < static_cast(src_depth.getSize()); ++i) { + for (int i = 0; i < src_depth_size; ++i) { if (!vpMath::isNaN(src_depth.bitmap[i])) { ++histogram[static_cast(src_depth.bitmap[i])]; } } - for (int i = 2; i < 0x10000; ++i) + for (int i = 2; i < 0x10000; ++i) { histogram[i] += histogram[i - 1]; // Build a cumulative histogram for the indices in [1,0xFFFF] - + } #ifdef VISP_HAVE_OPENMP #pragma omp parallel for #endif - for (int i = 0; i < static_cast(src_depth.getSize()); ++i) { + for (int i = 0; i < src_depth_size; ++i) { uint16_t d = static_cast(src_depth.bitmap[i]); if (d) { - unsigned char f = (unsigned char)(histogram[d] * 255 / histogram[0xFFFF]); // 0-255 based on histogram location + unsigned char f = static_cast((histogram[d] * 255) / histogram[0xFFFF]); // 0-255 based on histogram location dest_depth.bitmap[i].R = 255 - f; dest_depth.bitmap[i].G = 0; dest_depth.bitmap[i].B = f; @@ -221,24 +233,27 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage dest_depth.resize(src_depth.getHeight(), src_depth.getWidth()); uint32_t histogram[0x10000]; memset(histogram, 0, sizeof(histogram)); + int src_depth_size = static_cast(src_depth.getSize()); #ifdef VISP_HAVE_OPENMP #pragma omp parallel for #endif - for (int i = 0; i < static_cast(src_depth.getSize()); ++i) { + for (int i = 0; i < src_depth_size; ++i) { ++histogram[static_cast(src_depth.bitmap[i])]; } - for (unsigned int i = 2; i < 0x10000; ++i) + for (unsigned int i = 2; i < 0x10000; ++i) { histogram[i] += histogram[i - 1]; // Build a cumulative histogram for the indices in [1,0xFFFF] + } #ifdef VISP_HAVE_OPENMP #pragma omp parallel for #endif - for (int i = 0; i < static_cast(src_depth.getSize()); ++i) { + + for (int i = 0; i < src_depth_size; ++i) { uint16_t d = src_depth.bitmap[i]; if (d) { - unsigned char f = (unsigned char)(histogram[d] * 255 / histogram[0xFFFF]); // 0-255 based on histogram location + unsigned char f = static_cast((histogram[d] * 255) / histogram[0xFFFF]); // 0-255 based on histogram location dest_depth.bitmap[i].R = 255 - f; dest_depth.bitmap[i].G = 0; dest_depth.bitmap[i].B = f; @@ -252,5 +267,7 @@ void vp_createDepthHistogram(const vpImage &src_depth, vpImage } } } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/src/image/vpCannyEdgeDetection.cpp b/modules/core/src/image/vpCannyEdgeDetection.cpp index c1f55dcec6..0fd696bec0 100644 --- a/modules/core/src/image/vpCannyEdgeDetection.cpp +++ b/modules/core/src/image/vpCannyEdgeDetection.cpp @@ -39,7 +39,11 @@ namespace { // Helper to apply the scale to the raw values of the filters template -static void scaleFilter(vpArray2D &filter, const float &scale) +static void scaleFilter( +#if defined(ENABLE_VISP_NAMESPACE) + visp:: +#endif + vpArray2D &filter, const float &scale) { const unsigned int nbRows = filter.getRows(); const unsigned int nbCols = filter.getCols(); @@ -52,6 +56,10 @@ static void scaleFilter(vpArray2D &filter, const float &scale) }; #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif // // Initialization methods vpCannyEdgeDetection::vpCannyEdgeDetection() @@ -523,3 +531,6 @@ vpCannyEdgeDetection::recursiveSearchForStrongEdge(const std::pair #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpGaussianFilter::Impl { @@ -147,7 +151,9 @@ void vpGaussianFilter::apply(const vpImage &I, vpImage &I, vpImage &I_blur) { m_impl->apply(I, I_blur); } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpGaussianFilter.cpp.o) has no symbols void dummy_vpGaussianFilter() { }; diff --git a/modules/core/src/image/vpImageCircle.cpp b/modules/core/src/image/vpImageCircle.cpp index d21fbe1a00..ce35034320 100644 --- a/modules/core/src/image/vpImageCircle.cpp +++ b/modules/core/src/image/vpImageCircle.cpp @@ -34,6 +34,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif vpImageCircle::vpImageCircle() : m_center() , m_radius(0.) @@ -1164,3 +1168,6 @@ float vpImageCircle::get_n11() const { return 0.; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/image/vpImageConvert.cpp b/modules/core/src/image/vpImageConvert.cpp index 8328ff8bb3..d6abbd7306 100644 --- a/modules/core/src/image/vpImageConvert.cpp +++ b/modules/core/src/image/vpImageConvert.cpp @@ -30,8 +30,7 @@ * * Description: * Convert image types. - * -*****************************************************************************/ + */ /*! \file vpImageConvert.cpp @@ -47,14 +46,20 @@ #include -// image + +#ifndef VISP_SKIP_BAYER_CONVERSION #include "private/vpBayerConversion.h" +#endif #include "private/vpImageConvert_impl.h" #if defined(VISP_HAVE_SIMDLIB) #include #endif #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif bool vpImageConvert::YCbCrLUTcomputed = false; int vpImageConvert::vpCrr[256]; int vpImageConvert::vpCgb[256]; @@ -1133,7 +1138,7 @@ void vpImageConvert::RGBaToRGB(unsigned char *rgba, unsigned char *rgb, unsigned *(++pt_output) = *(++pt_input); // R *(++pt_output) = *(++pt_input); // G *(++pt_output) = *(++pt_input); // B - pt_input++; + ++pt_input; } #endif } @@ -1273,7 +1278,7 @@ void vpImageConvert::RGBaToGrey(unsigned char *rgba, unsigned char *grey, unsign while (pt_input != pt_end) { *pt_output = static_cast((0.2126 * (*pt_input)) + (0.7152 * (*(pt_input + 1))) + (0.0722 * (*(pt_input + 2)))); pt_input += 4; - pt_output++; + ++pt_output; } #endif } @@ -1321,12 +1326,12 @@ void vpImageConvert::GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsign while (pt_input != pt_end) { unsigned char p = *pt_input; - *(pt_output) = p; // R + *pt_output = p; // R *(pt_output + 1) = p; // G *(pt_output + 2) = p; // B *(pt_output + 3) = vpRGBa::alpha_default; // A - pt_input++; + ++pt_input; pt_output += 4; } #endif @@ -1353,11 +1358,11 @@ void vpImageConvert::GreyToRGB(unsigned char *grey, unsigned char *rgb, unsigned while (pt_input != pt_end) { unsigned char p = *pt_input; - *(pt_output) = p; // R + *pt_output = p; // R *(pt_output + 1) = p; // G *(pt_output + 2) = p; // B - pt_input++; + ++pt_input; pt_output += 3; } #endif @@ -1972,7 +1977,7 @@ void vpImageConvert::split(const vpImage &src, vpImage *p if ((tabChannel[j]->getHeight() != height) || (tabChannel[j]->getWidth() != width)) { tabChannel[j]->resize(height, width); } - dst = (unsigned char *)tabChannel[j]->bitmap; + dst = static_cast(tabChannel[j]->bitmap); input = (unsigned char *)src.bitmap + j; i = 0; @@ -1982,16 +1987,16 @@ void vpImageConvert::split(const vpImage &src, vpImage *p for (; i < n; i += 4) { *dst = *input; input += 4; - dst++; + ++dst; *dst = *input; input += 4; - dst++; + ++dst; *dst = *input; input += 4; dst++; *dst = *input; input += 4; - dst++; + ++dst; } n += 3; } @@ -1999,7 +2004,7 @@ void vpImageConvert::split(const vpImage &src, vpImage *p for (; i < n; ++i) { *dst = *input; input += 4; - dst++; + ++dst; } } } @@ -2132,7 +2137,7 @@ void vpImageConvert::MONO16ToRGBa(unsigned char *grey16, unsigned char *rgba, un } // Bilinear - +#ifndef VISP_SKIP_BAYER_CONVERSION /*! Converts an array of uint8 Bayer data to an array of interleaved R, G, B and A values using bilinear demosaicing method. @@ -2422,3 +2427,8 @@ void vpImageConvert::demosaicRGGBToRGBaMalvar(const uint16_t *rggb, uint16_t *rg { demosaicRGGBToRGBaMalvarTpl(rggb, rgba, width, height, nThreads); } +#endif // VISP_SKIP_BAYER_CONVERSION + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/image/vpImageConvert_hsv.cpp b/modules/core/src/image/vpImageConvert_hsv.cpp index 187cba2c64..647093e36f 100644 --- a/modules/core/src/image/vpImageConvert_hsv.cpp +++ b/modules/core/src/image/vpImageConvert_hsv.cpp @@ -45,6 +45,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * Convert an HSV image to a RGB or RGBa image depending on the value of \e step. * \param[in] hue_ : Image hue channel in range [0,1]. @@ -555,3 +559,6 @@ void vpImageConvert::RGBToHSV(const unsigned char *rgb, unsigned char *hue, unsi { vpImageConvert::RGB2HSV(rgb, hue, saturation, value, size, 3, h_full); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/image/vpImageConvert_pcl.cpp b/modules/core/src/image/vpImageConvert_pcl.cpp index 072ec4814e..d588f81dbd 100644 --- a/modules/core/src/image/vpImageConvert_pcl.cpp +++ b/modules/core/src/image/vpImageConvert_pcl.cpp @@ -48,6 +48,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * Create a point cloud from a depth image. * @@ -281,4 +285,7 @@ int vpImageConvert::depthToPointCloud(const vpImage &color, const vpImag return pcl_size; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/core/src/image/vpImageConvert_yuv.cpp b/modules/core/src/image/vpImageConvert_yuv.cpp index bec8f5a03a..c0a1f11dfb 100644 --- a/modules/core/src/image/vpImageConvert_yuv.cpp +++ b/modules/core/src/image/vpImageConvert_yuv.cpp @@ -54,6 +54,10 @@ void vpSAT(int &c) } }; +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Convert an image from YUYV 4:2:2 (y0 u01 y1 v01 y2 u23 y3 v23 ...) to RGB32. Destination rgba memory area has to be allocated before. @@ -1662,3 +1666,6 @@ void vpImageConvert::YVU9ToRGB(unsigned char *yuv, unsigned char *rgb, unsigned rgb += 9 * width; } } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/image/vpImageFilter.cpp b/modules/core/src/image/vpImageFilter.cpp index 6658d1f44c..a4070fc528 100644 --- a/modules/core/src/image/vpImageFilter.cpp +++ b/modules/core/src/image/vpImageFilter.cpp @@ -36,6 +36,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /** * \brief Get the list of available vpCannyBackendType. * @@ -1128,3 +1132,6 @@ void vpImageFilter::canny(const vpImage &Isrc, vpImage #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Check if an image point belongs to a rectangle. @@ -451,3 +455,6 @@ double vpImagePoint::sqrDistance(const vpImagePoint &iP1, const vpImagePoint &iP { 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/vpImageTools.cpp b/modules/core/src/image/vpImageTools.cpp index b4f180d622..e2867bfa7c 100644 --- a/modules/core/src/image/vpImageTools.cpp +++ b/modules/core/src/image/vpImageTools.cpp @@ -42,6 +42,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Change the look up table (LUT) of an image. Considering pixel gray level values \f$ l \f$ in the range \f$[A, B]\f$, this method allows @@ -155,7 +159,7 @@ void vpImageTools::imageDifference(const vpImage &I1, const vpIma SimdImageDifference(I1.bitmap, I2.bitmap, I1.getSize(), Idiff.bitmap); #else for (unsigned int i = 0; i < I1.getSize(); ++i) { - int diff = I1.bitmap[i] - I2.bitmap[i] + 128; + int diff = (I1.bitmap[i] - I2.bitmap[i]) + 128; Idiff.bitmap[i] = static_cast(std::max(std::min(diff, 255), 0)); } #endif @@ -191,11 +195,12 @@ void vpImageTools::imageDifference(const vpImage &I1, const vpImage(I1.bitmap), reinterpret_cast(I2.bitmap), I1.getSize() * 4, reinterpret_cast(Idiff.bitmap)); #else - for (unsigned int i = 0; i < I1.getSize() * 4; ++i) { - int diffR = I1.bitmap[i].R - I2.bitmap[i].R + 128; - int diffG = I1.bitmap[i].G - I2.bitmap[i].G + 128; - int diffB = I1.bitmap[i].B - I2.bitmap[i].B + 128; - int diffA = I1.bitmap[i].A - I2.bitmap[i].A + 128; + unsigned int i1_size = I1.getSize(); + for (unsigned int i = 0; i < (i1_size * 4); ++i) { + int diffR = (I1.bitmap[i].R - I2.bitmap[i].R) + 128; + int diffG = (I1.bitmap[i].G - I2.bitmap[i].G) + 128; + int diffB = (I1.bitmap[i].B - I2.bitmap[i].B) + 128; + int diffA = (I1.bitmap[i].A - I2.bitmap[i].A) + 128; Idiff.bitmap[i].R = static_cast(vpMath::maximum(vpMath::minimum(diffR, 255), 0)); Idiff.bitmap[i].G = static_cast(vpMath::maximum(vpMath::minimum(diffG, 255), 0)); Idiff.bitmap[i].B = static_cast(vpMath::maximum(vpMath::minimum(diffB, 255), 0)); @@ -328,8 +333,9 @@ void vpImageTools::imageAdd(const vpImage &I1, const vpImage((short int)*ptr_I1 + (short int)*ptr_I2) : *ptr_I1 + *ptr_I2; + unsigned int ires_size = Ires.getSize(); + for (unsigned int cpt = 0; cpt < ires_size; ++cpt, ++ptr_I1, ++ptr_I2, ++ptr_Ires) { + *ptr_Ires = saturate ? vpMath::saturate(static_cast(*ptr_I1) + static_cast(*ptr_I2)) : ((*ptr_I1) + (*ptr_I2)); } #endif } @@ -370,10 +376,11 @@ void vpImageTools::imageSubtract(const vpImage &I1, const vpImage unsigned char *ptr_I1 = I1.bitmap; unsigned char *ptr_I2 = I2.bitmap; unsigned char *ptr_Ires = Ires.bitmap; - for (unsigned int cpt = 0; cpt < Ires.getSize(); cpt++, ++ptr_I1, ++ptr_I2, ++ptr_Ires) { + unsigned int ires_size = Ires.getSize(); + for (unsigned int cpt = 0; cpt < ires_size; ++cpt, ++ptr_I1, ++ptr_I2, ++ptr_Ires) { *ptr_Ires = saturate ? vpMath::saturate(static_cast(*ptr_I1) - static_cast(*ptr_I2)) : - *ptr_I1 - *ptr_I2; + ((*ptr_I1) - (*ptr_I2)); } #endif } @@ -556,7 +563,8 @@ double vpImageTools::normalizedCorrelation(const vpImage &I1, const vpIm #if defined(VISP_HAVE_SIMDLIB) SimdNormalizedCorrelation(I1.bitmap, a, I2.bitmap, b, I1.getSize(), a2, b2, ab, useOptimized); #else - for (unsigned int cpt = 0; cpt < I1.getSize(); ++cpt) { + unsigned int i1_size = I1.getSize(); + for (unsigned int cpt = 0; cpt < i1_size; ++cpt) { ab += (I1.bitmap[cpt] - a) * (I2.bitmap[cpt] - b); a2 += vpMath::sqr(I1.bitmap[cpt] - a); b2 += vpMath::sqr(I2.bitmap[cpt] - b); @@ -833,8 +841,10 @@ double vpImageTools::normalizedCorrelation(const vpImage &I1, const vpIm #if defined(VISP_HAVE_SIMDLIB) SimdNormalizedCorrelation2(I1.bitmap, I1.getWidth(), I2.bitmap, I2.getWidth(), I2.getHeight(), i0, j0, ab); #else - for (unsigned int i = 0; i < I2.getHeight(); ++i) { - for (unsigned int j = 0; j < I2.getWidth(); ++j) { + unsigned int i2_height = I2.getHeight(); + unsigned int i2_width = I2.getWidth(); + for (unsigned int i = 0; i < i2_height; ++i) { + for (unsigned int j = 0; j < i2_width; ++j) { ab += (I1[i0 + i][j0 + j]) * I2[i][j]; } } @@ -924,7 +934,8 @@ void vpImageTools::remap(const vpImage &I, const vpArray2D &mapU, c mapV.data, mapDu.data, mapDv.data, reinterpret_cast(Iundist.bitmap)); #else const unsigned int i_ = static_cast(i); - for (unsigned int j = 0; j < I.getWidth(); ++j) { + unsigned int i_width = I.getWidth(); + for (unsigned int j = 0; j < i_width; ++j) { int u_round = mapU[i_][j]; int v_round = mapV[i_][j]; @@ -932,8 +943,8 @@ void vpImageTools::remap(const vpImage &I, const vpArray2D &mapU, c float du = mapDu[i_][j]; float dv = mapDv[i_][j]; - if (0 <= u_round && 0 <= v_round && u_round < static_cast(I.getWidth()) - 1 - && v_round < static_cast(I.getHeight()) - 1) { + if ((0 <= u_round) && (0 <= v_round) && (u_round < (static_cast(I.getWidth()) - 1)) + && (v_round < (static_cast(I.getHeight()) - 1))) { // process interpolation float col0 = lerp(I[v_round][u_round].R, I[v_round][u_round + 1].R, du); float col1 = lerp(I[v_round + 1][u_round].R, I[v_round + 1][u_round + 1].R, du); @@ -1184,3 +1195,6 @@ int vpImageTools::inRange(const unsigned char *hue, const unsigned char *saturat } return cpt_in_range; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/image/vpRGBa.cpp b/modules/core/src/image/vpRGBa.cpp index 3e8ec6a227..a46d1f5231 100644 --- a/modules/core/src/image/vpRGBa.cpp +++ b/modules/core/src/image/vpRGBa.cpp @@ -44,6 +44,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Copy operator (from an unsigned char value) @@ -258,3 +262,6 @@ 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 2979de6f81..ab4c977760 100644 --- a/modules/core/src/image/vpRGBf.cpp +++ b/modules/core/src/image/vpRGBf.cpp @@ -45,6 +45,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Copy operator (from a floating-point value) @@ -262,3 +266,6 @@ 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 35157bb1ae..0c72b2cd9a 100644 --- a/modules/core/src/math/matrix/vpColVector.cpp +++ b/modules/core/src/math/matrix/vpColVector.cpp @@ -57,6 +57,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif vpColVector vpColVector::operator+(const vpColVector &v) const { if (getRows() != v.getRows()) { @@ -1012,3 +1016,6 @@ void vpColVector::insert(const vpColVector &v, unsigned int r, unsigned int c) double vpColVector::euclideanNorm() const { return frobeniusNorm(); } #endif // defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/matrix/vpEigenConversion.cpp b/modules/core/src/math/matrix/vpEigenConversion.cpp index 075b99bd74..ee2e306856 100644 --- a/modules/core/src/math/matrix/vpEigenConversion.cpp +++ b/modules/core/src/math/matrix/vpEigenConversion.cpp @@ -35,7 +35,7 @@ #include -namespace vp +namespace VISP_EIGEN_CONVERSION_NAMESPACE { #ifdef VISP_HAVE_EIGEN3 /* Eigen to ViSP */ diff --git a/modules/core/src/math/matrix/vpMatrix.cpp b/modules/core/src/math/matrix/vpMatrix.cpp index 18fec0aecd..1ec2ee4f16 100644 --- a/modules/core/src/math/matrix/vpMatrix.cpp +++ b/modules/core/src/math/matrix/vpMatrix.cpp @@ -62,6 +62,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif #ifdef VISP_HAVE_LAPACK #ifdef VISP_HAVE_GSL #include @@ -499,8 +503,8 @@ void vpMatrix::transpose(vpMatrix &At) const // https://stackoverflow.com/a/21548079 const int tileSize = 32; for (unsigned int i = 0; i < rowNum; i += tileSize) { - for (unsigned int j = 0; j < colNum; j++) { - for (unsigned int b = 0; b < static_cast(tileSize) && i + b < rowNum; b++) { + for (unsigned int j = 0; j < colNum; ++j) { + for (unsigned int b = 0; ((b < static_cast(tileSize)) && ((i + b) < rowNum)); ++b) { At[j][i + b] = (*this)[i + b][j]; } } @@ -4995,10 +4999,10 @@ vpColVector vpMatrix::getCol(unsigned int j) const { return getCol(j, 0, rowNum) A.print(std::cout, 4); - vpRowVector rv = A.getRow(1); - std::cout << "Row vector: \n" << rv << std::endl; +vpRowVector rv = A.getRow(1); +std::cout << "Row vector: \n" << rv << std::endl; } - \endcode +\endcode It produces the following output : \code [4, 4] = @@ -6722,3 +6726,6 @@ void vpMatrix::setIdentity(const double &val) } #endif //#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/matrix/vpMatrix_cholesky.cpp b/modules/core/src/math/matrix/vpMatrix_cholesky.cpp index 30ae5de122..a68d19f570 100644 --- a/modules/core/src/math/matrix/vpMatrix_cholesky.cpp +++ b/modules/core/src/math/matrix/vpMatrix_cholesky.cpp @@ -30,11 +30,7 @@ * * Description: * Matrix Cholesky decomposition. - * - * Authors: - * Filip Novotny - * -*****************************************************************************/ + */ #include @@ -71,6 +67,14 @@ extern "C" int dpotri_(char *uplo, integer *n, double *a, integer *lda, integer #endif #endif +#if defined(VISP_HAVE_EIGEN3) +#include +#endif + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Compute the inverse of a n-by-n matrix using the Cholesky decomposition. The matrix must be real symmetric positive defined. @@ -85,30 +89,29 @@ extern "C" int dpotri_(char *uplo, integer *n, double *a, integer *lda, integer Here an example: \code -#include + #include -int main() -{ - vpMatrix A(4,4); + int main() + { + vpMatrix A(4,4); - // Symmetric matrix - A[0][0] = 1/1.; A[0][1] = 1/5.; A[0][2] = 1/6.; A[0][3] = 1/7.; - A[1][0] = 1/5.; A[1][1] = 1/3.; A[1][2] = 1/3.; A[1][3] = 1/5.; - A[2][0] = 1/6.; A[2][1] = 1/3.; A[2][2] = 1/2.; A[2][3] = 1/6.; - A[3][0] = 1/7.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; + // Symmetric matrix + A[0][0] = 1/1.; A[0][1] = 1/5.; A[0][2] = 1/6.; A[0][3] = 1/7.; + A[1][0] = 1/5.; A[1][1] = 1/3.; A[1][2] = 1/3.; A[1][3] = 1/5.; + A[2][0] = 1/6.; A[2][1] = 1/3.; A[2][2] = 1/2.; A[2][3] = 1/6.; + A[3][0] = 1/7.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; - // Compute the inverse - vpMatrix A_1; // A^-1 - A_1 = A.inverseByCholesky(); - std::cout << "Inverse by Cholesky: \n" << A_1 << std::endl; + // Compute the inverse + vpMatrix A_1; // A^-1 + A_1 = A.inverseByCholesky(); + std::cout << "Inverse by Cholesky: \n" << A_1 << std::endl; - std::cout << "A*A^-1: \n" << A * A_1 << std::endl; -} + std::cout << "A*A^-1: \n" << A * A_1 << std::endl; + } \endcode \sa pseudoInverse() */ - vpMatrix vpMatrix::inverseByCholesky() const { #if defined(VISP_HAVE_LAPACK) @@ -123,36 +126,36 @@ vpMatrix vpMatrix::inverseByCholesky() const #if defined(VISP_HAVE_LAPACK) /*! Compute the inverse of a n-by-n matrix using the Cholesky decomposition with -Lapack 3rd party. The matrix must be real symmetric positive defined. + Lapack 3rd party. The matrix must be real symmetric positive defined. \return The inverse matrix. Here an example: \code -#include + #include -int main() -{ - unsigned int n = 4; - vpMatrix A(n, n); - vpMatrix I; - I.eye(4); + int main() + { + unsigned int n = 4; + vpMatrix A(n, n); + vpMatrix I; + I.eye(4); - A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; A[0][3] = 1/4.; - A[1][0] = 1/5.; A[1][1] = 1/3.; A[1][2] = 1/3.; A[1][3] = 1/5.; - A[2][0] = 1/6.; A[2][1] = 1/4.; A[2][2] = 1/2.; A[2][3] = 1/6.; - A[3][0] = 1/7.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; + A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; A[0][3] = 1/4.; + A[1][0] = 1/5.; A[1][1] = 1/3.; A[1][2] = 1/3.; A[1][3] = 1/5.; + A[2][0] = 1/6.; A[2][1] = 1/4.; A[2][2] = 1/2.; A[2][3] = 1/6.; + A[3][0] = 1/7.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; - // Make matrix symmetric positive - A = 0.5*(A+A.t()); - A = A + n*I; + // Make matrix symmetric positive + A = 0.5*(A+A.t()); + A = A + n*I; - // Compute the inverse - vpMatrix A_1 = A.inverseByCholeskyLapack(); - std::cout << "Inverse by Cholesky (Lapack): \n" << A_1 << std::endl; + // Compute the inverse + vpMatrix A_1 = A.inverseByCholeskyLapack(); + std::cout << "Inverse by Cholesky (Lapack): \n" << A_1 << std::endl; - std::cout << "A*A^-1: \n" << A * A_1 << std::endl; -} + std::cout << "A*A^-1: \n" << A * A_1 << std::endl; + } \endcode \sa inverseByCholesky(), inverseByCholeskyOpenCV() @@ -267,7 +270,7 @@ vpMatrix vpMatrix::choleskyByLapack()const } return L; } -#endif +#endif // VISP_HAVE_LAPACK #if defined(VISP_HAVE_OPENCV) /*! @@ -278,30 +281,30 @@ vpMatrix vpMatrix::choleskyByLapack()const Here an example: \code -#include + #include -int main() -{ - unsigned int n = 4; - vpMatrix A(n, n); - vpMatrix I; - I.eye(4); + int main() + { + unsigned int n = 4; + vpMatrix A(n, n); + vpMatrix I; + I.eye(4); - A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; A[0][3] = 1/4.; - A[1][0] = 1/5.; A[1][1] = 1/3.; A[1][2] = 1/3.; A[1][3] = 1/5.; - A[2][0] = 1/6.; A[2][1] = 1/4.; A[2][2] = 1/2.; A[2][3] = 1/6.; - A[3][0] = 1/7.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; + A[0][0] = 1/1.; A[0][1] = 1/2.; A[0][2] = 1/3.; A[0][3] = 1/4.; + A[1][0] = 1/5.; A[1][1] = 1/3.; A[1][2] = 1/3.; A[1][3] = 1/5.; + A[2][0] = 1/6.; A[2][1] = 1/4.; A[2][2] = 1/2.; A[2][3] = 1/6.; + A[3][0] = 1/7.; A[3][1] = 1/5.; A[3][2] = 1/6.; A[3][3] = 1/7.; - // Make matrix symmetric positive - A = 0.5*(A+A.t()); - A = A + n*I; + // Make matrix symmetric positive + A = 0.5*(A+A.t()); + A = A + n*I; - // Compute the inverse - vpMatrix A_1 = A.inverseByCholeskyOpenCV(); - std::cout << "Inverse by Cholesky (OpenCV): \n" << A_1 << std::endl; + // Compute the inverse + vpMatrix A_1 = A.inverseByCholeskyOpenCV(); + std::cout << "Inverse by Cholesky (OpenCV): \n" << A_1 << std::endl; - std::cout << "A*A^-1: \n" << A * A_1 << std::endl; -} + std::cout << "A*A^-1: \n" << A * A_1 << std::endl; + } \endcode \sa inverseByCholesky(), inverseByCholeskyLapack() @@ -349,10 +352,9 @@ vpMatrix vpMatrix::choleskyByOpenCV() const } return L; } -#endif +#endif // VISP_HAVE_OPENCV #if defined(VISP_HAVE_EIGEN3) -#include /*! * \brief Compute the Cholesky decomposition of a Hermitian positive-definite matrix * using Eigen3 library. @@ -378,4 +380,8 @@ vpMatrix vpMatrix::choleskyByEigen3() const } return Lvisp; } +#endif // VISP_HAVE_EIGEN3 + +#if defined(ENABLE_VISP_NAMESPACE) +} #endif diff --git a/modules/core/src/math/matrix/vpMatrix_covariance.cpp b/modules/core/src/math/matrix/vpMatrix_covariance.cpp index 1caa73ec38..9e3b044aef 100644 --- a/modules/core/src/math/matrix/vpMatrix_covariance.cpp +++ b/modules/core/src/math/matrix/vpMatrix_covariance.cpp @@ -46,6 +46,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Compute the covariance matrix of the parameters x from a least squares minimization defined as: Ax = b @@ -231,3 +235,6 @@ void vpMatrix::computeCovarianceMatrixVVS(const vpHomogeneousMatrix &cMo, const // building deltaP deltaP = Js.pseudoInverse(Js.getRows() * std::numeric_limits::epsilon()) * deltaS; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/matrix/vpMatrix_lu.cpp b/modules/core/src/math/matrix/vpMatrix_lu.cpp index 6b265f1f9f..7c42b094ae 100644 --- a/modules/core/src/math/matrix/vpMatrix_lu.cpp +++ b/modules/core/src/math/matrix/vpMatrix_lu.cpp @@ -74,6 +74,10 @@ extern "C" void dgetri_(integer *n, double *a, integer *lda, integer *ipiv, doub #include // std::fabs #include // numeric_limits +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*-------------------------------------------------------------------- LU Decomposition related functions -------------------------------------------------------------------- */ @@ -625,3 +629,6 @@ double vpMatrix::detByLUEigen3() const return M.determinant(); } #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/matrix/vpMatrix_mul.cpp b/modules/core/src/math/matrix/vpMatrix_mul.cpp index 15a61f61f1..e0aecb1430 100644 --- a/modules/core/src/math/matrix/vpMatrix_mul.cpp +++ b/modules/core/src/math/matrix/vpMatrix_mul.cpp @@ -44,6 +44,10 @@ // or vector content in a gsl_matrix or gsl_vector. This is not acceptable here. // that's why we prefer use naive code when VISP_HAVE_GSL is defined. #if defined(VISP_HAVE_LAPACK) +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif #ifdef VISP_HAVE_MKL #include typedef MKL_INT integer; @@ -112,10 +116,13 @@ void vpMatrix::blas_dgemv(char trans, unsigned int M_, unsigned int N_, double a dgemv_(&trans, &M, &N, &alpha, a_data, &lda, x_data, &incx, &beta, y_data, &incy); } #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #else // Work around to avoid warning LNK4221: This object file does not define any // previously undefined public symbols -void dummy_vpMatrix_blas(){}; +void dummy_vpMatrix_blas() { }; #endif #endif // #ifndef DOXYGEN_SHOULD_SKIP_THIS diff --git a/modules/core/src/math/matrix/vpMatrix_qr.cpp b/modules/core/src/math/matrix/vpMatrix_qr.cpp index b770626cd3..f80a2e6b72 100644 --- a/modules/core/src/math/matrix/vpMatrix_qr.cpp +++ b/modules/core/src/math/matrix/vpMatrix_qr.cpp @@ -52,6 +52,10 @@ // Debug trace #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif #ifdef VISP_HAVE_LAPACK #ifdef VISP_HAVE_GSL #if !(GSL_MAJOR_VERSION >= 2 && GSL_MINOR_VERSION >= 2) @@ -1208,3 +1212,6 @@ vpColVector vpMatrix::solveByQR(const vpColVector &b) const solveByQR(b, x); return x; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/matrix/vpMatrix_svd.cpp b/modules/core/src/math/matrix/vpMatrix_svd.cpp index f45551e674..7f5f5ec57a 100644 --- a/modules/core/src/math/matrix/vpMatrix_svd.cpp +++ b/modules/core/src/math/matrix/vpMatrix_svd.cpp @@ -73,6 +73,11 @@ extern "C" int dgesdd_(char *jobz, integer *m, integer *n, double *a, integer *l #include #endif #endif + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*--------------------------------------------------------------------- SVD related functions @@ -466,3 +471,6 @@ void vpMatrix::svdEigen3(vpColVector &w, vpMatrix &V) U_ = svd.matrixU(); } #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/matrix/vpRowVector.cpp b/modules/core/src/math/matrix/vpRowVector.cpp index 464ff165c8..fb488de875 100644 --- a/modules/core/src/math/matrix/vpRowVector.cpp +++ b/modules/core/src/math/matrix/vpRowVector.cpp @@ -51,6 +51,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif //! Copy operator. Allow operation such as A = v vpRowVector &vpRowVector::operator=(const vpRowVector &v) { @@ -769,7 +773,7 @@ v: 0 10 11 3 */ void vpRowVector::insert(unsigned int i, const vpRowVector &v) { - if ( (i + v.size()) > this->size()) { + if ((i + v.size()) > this->size()) { throw(vpException(vpException::dimensionError, "Unable to insert (1x%d) row vector in (1x%d) row " "vector at position (%d)", @@ -1067,7 +1071,7 @@ int vpRowVector::print(std::ostream &s, unsigned int length, char const *intro) } else { assert(maxAfter > 1); - s.width( static_cast (maxAfter)); + s.width(static_cast (maxAfter)); s << ".0"; } } @@ -1366,3 +1370,6 @@ std::ostream &vpRowVector::matlabPrint(std::ostream &os) const os << "]" << std::endl; return os; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/matrix/vpSubColVector.cpp b/modules/core/src/math/matrix/vpSubColVector.cpp index bdebd53e90..b458ab47f0 100644 --- a/modules/core/src/math/matrix/vpSubColVector.cpp +++ b/modules/core/src/math/matrix/vpSubColVector.cpp @@ -41,6 +41,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif //! Default constructor that creates an empty vector. vpSubColVector::vpSubColVector() : vpColVector(), m_pRowNum(0), m_parent(nullptr) { } @@ -247,3 +251,6 @@ vpSubColVector &vpSubColVector::operator=(const vpPoseVector &p) memcpy(data, p.data, rowNum * sizeof(double)); return *this; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/matrix/vpSubMatrix.cpp b/modules/core/src/math/matrix/vpSubMatrix.cpp index 763980f7f4..2760aefcb4 100644 --- a/modules/core/src/math/matrix/vpSubMatrix.cpp +++ b/modules/core/src/math/matrix/vpSubMatrix.cpp @@ -42,6 +42,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif vpSubMatrix::vpSubMatrix() : pRowNum(0), pColNum(0), parent(nullptr) { } /*! @@ -180,3 +184,6 @@ vpSubMatrix &vpSubMatrix::operator=(const double &x) } vpSubMatrix::~vpSubMatrix() { data = nullptr; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/matrix/vpSubRowVector.cpp b/modules/core/src/math/matrix/vpSubRowVector.cpp index f826982e6d..6fb6181788 100644 --- a/modules/core/src/math/matrix/vpSubRowVector.cpp +++ b/modules/core/src/math/matrix/vpSubRowVector.cpp @@ -36,6 +36,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif //! Default constructor that creates an empty vector. vpSubRowVector::vpSubRowVector() : vpRowVector(), m_pColNum(0), m_parent(nullptr) { } @@ -181,3 +185,6 @@ vpSubRowVector &vpSubRowVector::operator=(const double &x) } return *this; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/misc/vpMath.cpp b/modules/core/src/math/misc/vpMath.cpp index 2e6683d478..b025958c7a 100644 --- a/modules/core/src/math/misc/vpMath.cpp +++ b/modules/core/src/math/misc/vpMath.cpp @@ -54,6 +54,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif #if !(defined(VISP_HAVE_FUNC_ISNAN) || defined(VISP_HAVE_FUNC_STD_ISNAN)) || \ !(defined(VISP_HAVE_FUNC_ISINF) || defined(VISP_HAVE_FUNC_STD_ISINF)) || \ !(defined(VISP_HAVE_FUNC_ISFINITE) || defined(VISP_HAVE_FUNC_STD_ISFINITE) || defined(VISP_HAVE_FUNC__FINITE)) @@ -762,3 +766,6 @@ vpHomogeneousMatrix vpMath::enu2ned(const vpHomogeneousMatrix &enu_M) vpHomogeneousMatrix ned_M = ned_M_enu * enu_M; return ned_M; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/random-generator/vpUniRand.cpp b/modules/core/src/math/random-generator/vpUniRand.cpp index 10335a504a..31d2dfcbb7 100644 --- a/modules/core/src/math/random-generator/vpUniRand.cpp +++ b/modules/core/src/math/random-generator/vpUniRand.cpp @@ -69,6 +69,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif vpUniRand::vpUniRand() : m_maxInvDbl(1.0 / static_cast(UINT32_MAX)), m_maxInvFlt(1.0f / static_cast(UINT32_MAX)), m_rng() { } @@ -207,3 +211,6 @@ void vpUniRand::setSeed(uint64_t initstate, uint64_t initseq) m_rng.state += initstate; next(); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/robust/vpRobust.cpp b/modules/core/src/math/robust/vpRobust.cpp index c781df403b..b178661c48 100644 --- a/modules/core/src/math/robust/vpRobust.cpp +++ b/modules/core/src/math/robust/vpRobust.cpp @@ -53,6 +53,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Default constructor. */ @@ -705,3 +709,6 @@ double vpRobust::gammln(double xx) #undef vpEPS #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/transformation/vpExponentialMap.cpp b/modules/core/src/math/transformation/vpExponentialMap.cpp index 0fe64c478d..f1472dde02 100644 --- a/modules/core/src/math/transformation/vpExponentialMap.cpp +++ b/modules/core/src/math/transformation/vpExponentialMap.cpp @@ -38,6 +38,10 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Compute the exponential map. The inverse function is inverse(). The @@ -285,3 +289,6 @@ vpColVector vpExponentialMap::inverse(const vpHomogeneousMatrix &M, const double return v; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/transformation/vpForceTwistMatrix.cpp b/modules/core/src/math/transformation/vpForceTwistMatrix.cpp index 351d127eec..b97e0e8c77 100644 --- a/modules/core/src/math/transformation/vpForceTwistMatrix.cpp +++ b/modules/core/src/math/transformation/vpForceTwistMatrix.cpp @@ -34,13 +34,6 @@ * *****************************************************************************/ -#include -#include - -#include -#include -#include - /*! \file vpForceTwistMatrix.cpp @@ -49,6 +42,18 @@ transform a force/torque skew from one frame to an other. */ +#include +#include + +#include +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! Copy operator. @@ -788,3 +793,6 @@ int vpForceTwistMatrix::print(std::ostream &s, unsigned int length, char const * void vpForceTwistMatrix::setIdentity() { eye(); } #endif //#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +#if defined(ENABLE_VISP_NAMESPACE) + } +#endif diff --git a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp index 206919ad22..8db2b1ab77 100644 --- a/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp +++ b/modules/core/src/math/transformation/vpHomogeneousMatrix.cpp @@ -46,6 +46,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Construct an homogeneous matrix from a translation vector and quaternion rotation vector. @@ -1379,6 +1383,9 @@ void vpHomogeneousMatrix::convert_to_json(nlohmann::json &j) const void vpHomogeneousMatrix::parse_json(const nlohmann::json &j) { +#if defined(ENABLE_VISP_NAMESPACE) + using namespace visp; +#endif vpArray2D *asArray = (vpArray2D*) this; if (j.is_object() && j.contains("type")) { // Specific conversions const bool converted = convertFromTypeAndBuildFrom(j, *this); @@ -1398,3 +1405,6 @@ void vpHomogeneousMatrix::parse_json(const nlohmann::json &j) } } #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/transformation/vpPoseVector.cpp b/modules/core/src/math/transformation/vpPoseVector.cpp index e2e517ce95..f2461ec9d2 100644 --- a/modules/core/src/math/transformation/vpPoseVector.cpp +++ b/modules/core/src/math/transformation/vpPoseVector.cpp @@ -49,6 +49,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! Default constructor that construct a 6 dimension pose vector \f$ [\bf t, @@ -610,6 +615,9 @@ void vpPoseVector::convert_to_json(nlohmann::json &j) const } void vpPoseVector::parse_json(const nlohmann::json &j) { +#if defined(ENABLE_VISP_NAMESPACE) + using namespace visp; +#endif vpArray2D *asArray = (vpArray2D*) this; if (j.is_object() && j.contains("type")) { // Specific conversions const bool converted = convertFromTypeAndBuildFrom(j, *this); @@ -626,3 +634,6 @@ void vpPoseVector::parse_json(const nlohmann::json &j) } } #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/transformation/vpQuaternionVector.cpp b/modules/core/src/math/transformation/vpQuaternionVector.cpp index 53a9731800..2cd55c12a4 100644 --- a/modules/core/src/math/transformation/vpQuaternionVector.cpp +++ b/modules/core/src/math/transformation/vpQuaternionVector.cpp @@ -43,6 +43,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif // minimum value of sine const double vpQuaternionVector::minimum = 0.0001; @@ -549,3 +553,6 @@ vpQuaternionVector vpQuaternionVector::slerp(const vpQuaternionVector &q0, const return qSlerp; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/transformation/vpRotationMatrix.cpp b/modules/core/src/math/transformation/vpRotationMatrix.cpp index a0ca634dff..209d6a7e7b 100644 --- a/modules/core/src/math/transformation/vpRotationMatrix.cpp +++ b/modules/core/src/math/transformation/vpRotationMatrix.cpp @@ -52,6 +52,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Initialize the rotation matrix as identity. @@ -1138,3 +1142,6 @@ void vpRotationMatrix::orthogonalize() void vpRotationMatrix::setIdentity() { eye(); } #endif //#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/transformation/vpRotationVector.cpp b/modules/core/src/math/transformation/vpRotationVector.cpp index 3c895fccfd..e26688380d 100644 --- a/modules/core/src/math/transformation/vpRotationVector.cpp +++ b/modules/core/src/math/transformation/vpRotationVector.cpp @@ -33,6 +33,12 @@ * *****************************************************************************/ +/*! + \file vpRotationVector.cpp + \brief Class that consider the case of a generic rotation vector + (cannot be used as is !). +*/ + #include #include @@ -40,12 +46,10 @@ #include #include -/*! - \file vpRotationVector.cpp - \brief Class that consider the case of a generic rotation vector - (cannot be used as is !). -*/ - +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Return the transpose of the rotation vector. @@ -162,7 +166,7 @@ tu: 0 1.570796327 3.141592654 */ vpRotationVector &vpRotationVector::operator,(double val) { - m_index++; + ++m_index; if (m_index >= size()) { throw(vpException(vpException::dimensionError, "Cannot set rotation vector out of bounds. It has only %d elements while you try to initialize " @@ -190,3 +194,6 @@ double vpRotationVector::sumSquare() const return sum_square; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/transformation/vpRxyzVector.cpp b/modules/core/src/math/transformation/vpRxyzVector.cpp index 144b236ea9..bc4a936f20 100644 --- a/modules/core/src/math/transformation/vpRxyzVector.cpp +++ b/modules/core/src/math/transformation/vpRxyzVector.cpp @@ -33,16 +33,20 @@ * Rxyz(phi,theta,psi) = Rot(x,phi)Rot(y,theta)Rot(z,psi). */ -#include - -#include - /*! \file vpRxyzVector.cpp \brief class that consider the case of the Rxyz angle parameterization for the rotation : Rxyz(phi,theta,psi) = Rot(x,phi)Rot(y,theta)Rot(z,psi) */ +#include + +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Default constructor that initialize all the 3 angles to zero. */ vpRxyzVector::vpRxyzVector() : vpRotationVector(3) { } @@ -322,3 +326,6 @@ vpRxyzVector &vpRxyzVector::operator=(const std::initializer_list &list) return *this; } #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/transformation/vpRzyxVector.cpp b/modules/core/src/math/transformation/vpRzyxVector.cpp index 4dfc849933..b12de39431 100644 --- a/modules/core/src/math/transformation/vpRzyxVector.cpp +++ b/modules/core/src/math/transformation/vpRzyxVector.cpp @@ -34,8 +34,6 @@ * *****************************************************************************/ -#include -#include /*! \file vpRzyxVector.cpp \brief class that consider the case of the Rzyx angle parameterization for @@ -43,6 +41,13 @@ */ +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Default constructor that initialize all the 3 angles to zero. */ vpRzyxVector::vpRzyxVector() : vpRotationVector(3) { } @@ -338,3 +343,6 @@ vpRzyxVector &vpRzyxVector::operator=(const std::initializer_list &list) return *this; } #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/transformation/vpRzyzVector.cpp b/modules/core/src/math/transformation/vpRzyzVector.cpp index 4de914d006..339533d40a 100644 --- a/modules/core/src/math/transformation/vpRzyzVector.cpp +++ b/modules/core/src/math/transformation/vpRzyzVector.cpp @@ -33,15 +33,19 @@ * Rzyz(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(z,psi) */ -#include -#include - /*! \file vpRzyzVector.cpp \brief class that consider the case of the Rzyz angle parameterization for the rotation : Rzyz(phi,theta,psi) = Rot(z,phi)Rot(y,theta)Rot(z,psi) */ +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Default constructor that initialize all the 3 angles to zero. */ vpRzyzVector::vpRzyzVector() : vpRotationVector(3) { } /*! Copy constructor. */ @@ -319,3 +323,6 @@ vpRzyzVector &vpRzyzVector::operator=(const std::initializer_list &list) return *this; } #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/transformation/vpThetaUVector.cpp b/modules/core/src/math/transformation/vpThetaUVector.cpp index 7a6758ebcd..b4cc60c079 100644 --- a/modules/core/src/math/transformation/vpThetaUVector.cpp +++ b/modules/core/src/math/transformation/vpThetaUVector.cpp @@ -42,6 +42,10 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif const double vpThetaUVector::minimum = 0.0001; /*! Default constructor that initialize all the 3 angles to zero. */ @@ -616,3 +620,6 @@ vpThetaUVector &vpThetaUVector::operator=(const std::initializer_list &l return *this; } #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/transformation/vpTranslationVector.cpp b/modules/core/src/math/transformation/vpTranslationVector.cpp index 32e71f7bc0..3082c0148d 100644 --- a/modules/core/src/math/transformation/vpTranslationVector.cpp +++ b/modules/core/src/math/transformation/vpTranslationVector.cpp @@ -32,16 +32,20 @@ * Translation vector. */ -#include -#include - -#include - /*! \file vpTranslationVector.cpp \brief Class that consider the case of a translation vector. */ +#include +#include + +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Construct a translation vector \f$ \bf t \f$ from 3 doubles. @@ -868,3 +872,6 @@ vpTranslationVector vpTranslationVector::mean(const std::vector -#include - -#include -#include - /*! \file vpVelocityTwistMatrix.cpp @@ -47,6 +41,16 @@ transform a velocity skew from one frame to an other. */ +#include +#include + +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Copy operator that allow to set a velocity twist matrix from an other one. @@ -719,3 +723,6 @@ int vpVelocityTwistMatrix::print(std::ostream &s, unsigned int length, char cons void vpVelocityTwistMatrix::setIdentity() { eye(); } #endif // #if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/math/transformation/vpXmlParserHomogeneousMatrix.cpp b/modules/core/src/math/transformation/vpXmlParserHomogeneousMatrix.cpp index edcff25c1d..42ea6c2d0b 100644 --- a/modules/core/src/math/transformation/vpXmlParserHomogeneousMatrix.cpp +++ b/modules/core/src/math/transformation/vpXmlParserHomogeneousMatrix.cpp @@ -62,6 +62,10 @@ #define LABEL_XML_TUY "theta_uy" #define LABEL_XML_TUZ "theta_uz" +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpXmlParserHomogeneousMatrix::Impl { @@ -556,7 +560,9 @@ void vpXmlParserHomogeneousMatrix::setHomogeneousMatrixName(const std::string &n { m_impl->setHomogeneousMatrixName(name); } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpXmlParserHomogeneousMatrix.cpp.o) has no symbols void dummy_vpXmlParserHomogeneousMatrix() { }; diff --git a/modules/core/src/tools/cpu-features/vpCPUFeatures.cpp b/modules/core/src/tools/cpu-features/vpCPUFeatures.cpp index 333d586e08..fa593cfb31 100644 --- a/modules/core/src/tools/cpu-features/vpCPUFeatures.cpp +++ b/modules/core/src/tools/cpu-features/vpCPUFeatures.cpp @@ -40,6 +40,10 @@ #endif #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif namespace vpCPUFeatures { // TODO: try to refactor to keep only SimdCpuInfo code and remove cpu_x86 code? @@ -71,3 +75,6 @@ bool checkNeon() { return SimdCpuInfo(SimdCpuInfoNeon) != 0; } void printCPUInfo() { cpu_features.print(); } } // namespace vpCPUFeatures +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tools/endian/vpEndian.cpp b/modules/core/src/tools/endian/vpEndian.cpp index 234e19f1c8..5166911f22 100644 --- a/modules/core/src/tools/endian/vpEndian.cpp +++ b/modules/core/src/tools/endian/vpEndian.cpp @@ -40,6 +40,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif namespace vpEndian { /*! @@ -64,7 +68,8 @@ uint32_t swap32bits(uint32_t val) */ float swapFloat(float f) { - union { + union + { float f; unsigned char b[4]; } dat1, dat2; @@ -83,7 +88,8 @@ float swapFloat(float f) */ double swapDouble(double d) { - union { + union + { double d; unsigned char b[8]; } dat1, dat2; @@ -116,3 +122,6 @@ uint16_t reinterpret_cast_uchar_to_uint16_LE(unsigned char *const ptr) #endif } } // namespace vpEndian +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tools/exceptions/vpException.cpp b/modules/core/src/tools/exceptions/vpException.cpp index 8dd97bf362..2c2ee7df09 100644 --- a/modules/core/src/tools/exceptions/vpException.cpp +++ b/modules/core/src/tools/exceptions/vpException.cpp @@ -39,9 +39,13 @@ #include "visp3/core/vpException.h" #include -vpException::vpException(int id) : code(id), message() {} +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif +vpException::vpException(int id) : code(id), message() { } -vpException::vpException(int id, const std::string &msg) : code(id), message(msg) {} +vpException::vpException(int id, const std::string &msg) : code(id), message(msg) { } vpException::vpException(int id, const char *format, ...) : code(id), message() { @@ -75,3 +79,6 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, const vpException &error) return os; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tools/file/vpIoTools.cpp b/modules/core/src/tools/file/vpIoTools.cpp index 42cbd30975..cfdbb9c5e1 100644 --- a/modules/core/src/tools/file/vpIoTools.cpp +++ b/modules/core/src/tools/file/vpIoTools.cpp @@ -486,6 +486,10 @@ visp::cnpy::NpyArray visp::cnpy::npy_load(std::string fname) #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif std::string vpIoTools::baseName = ""; std::string vpIoTools::baseDir = ""; std::string vpIoTools::configFile = ""; @@ -498,6 +502,9 @@ const char vpIoTools::separator = #else '/'; #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif namespace { @@ -538,6 +545,10 @@ std::string &rtrim(std::string &s) } } // namespace +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Return build informations (OS, compiler, build flags, used 3rd parties...). */ @@ -2121,16 +2132,16 @@ std::string vpIoTools::toLowerCase(const std::string &input) out += std::tolower(*it); } return out; -} + } -/** - * @brief Return a upper-case version of the string \b input . - * Numbers and special characters stay the same - * - * @param input The input string for which we want to ensure that all the characters are in upper case. - * @return std::string A upper-case version of the string \b input, where - * numbers and special characters stay the same - */ + /** + * @brief Return a upper-case version of the string \b input . + * Numbers and special characters stay the same + * + * @param input The input string for which we want to ensure that all the characters are in upper case. + * @return std::string A upper-case version of the string \b input, where + * numbers and special characters stay the same + */ std::string vpIoTools::toUpperCase(const std::string &input) { std::string out; @@ -2142,16 +2153,16 @@ std::string vpIoTools::toUpperCase(const std::string &input) out += std::toupper(*it); } return out; -} + } -/*! - Returns the absolute path using realpath() on Unix systems or - GetFullPathName() on Windows systems. \return According to realpath() - manual, returns an absolute pathname that names the same file, whose - resolution does not involve '.', '..', or symbolic links for Unix systems. - According to GetFullPathName() documentation, retrieves the full path of the - specified file for Windows systems. - */ + /*! + Returns the absolute path using realpath() on Unix systems or + GetFullPathName() on Windows systems. \return According to realpath() + manual, returns an absolute pathname that names the same file, whose + resolution does not involve '.', '..', or symbolic links for Unix systems. + According to GetFullPathName() documentation, retrieves the full path of the + specified file for Windows systems. + */ std::string vpIoTools::getAbsolutePathname(const std::string &pathname) { @@ -2693,3 +2704,6 @@ bool vpIoTools::parseBoolean(std::string input) Remove leading and trailing whitespaces from a string. */ std::string vpIoTools::trim(std::string s) { return ltrim(rtrim(s)); } +#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 1abdd1c96a..8837153155 100644 --- a/modules/core/src/tools/geometry/vpPlane.cpp +++ b/modules/core/src/tools/geometry/vpPlane.cpp @@ -43,6 +43,10 @@ #include // std::fabs #include // numeric_limits +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Copy operator. */ @@ -389,3 +393,6 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &os, 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/vpPolygon.cpp b/modules/core/src/tools/geometry/vpPolygon.cpp index 1bc06c352a..969b6e4cbc 100644 --- a/modules/core/src/tools/geometry/vpPolygon.cpp +++ b/modules/core/src/tools/geometry/vpPolygon.cpp @@ -44,6 +44,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif // Local helper #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_IMGPROC) @@ -696,3 +700,6 @@ unsigned int vpPolygon::getSize() const { return (static_cast(_corners.size())); } +#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 8540789159..6bbe4c053e 100644 --- a/modules/core/src/tools/geometry/vpRect.cpp +++ b/modules/core/src/tools/geometry/vpRect.cpp @@ -42,6 +42,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Constructs a default rectangle with the \e top, \e left corner set to (0,0) and \e width and \e height set to 1. @@ -271,3 +275,6 @@ 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/geometry/vpRectOriented.cpp b/modules/core/src/tools/geometry/vpRectOriented.cpp index 794edeebec..fff4d2ca29 100644 --- a/modules/core/src/tools/geometry/vpRectOriented.cpp +++ b/modules/core/src/tools/geometry/vpRectOriented.cpp @@ -36,6 +36,10 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /// Default constructor. vpRectOriented::vpRectOriented() : m_center(), m_width(), m_height(), m_theta(), m_topLeft(), m_topRight(), m_bottomLeft(), m_bottomRight() @@ -246,3 +250,6 @@ bool vpRectOriented::isLeft(const vpImagePoint &pointToTest, const vpImagePoint double d = (a * pointToTest.get_i()) + (b * pointToTest.get_j()) + c; return (d > 0); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tools/geometry/vpXmlParserRectOriented.cpp b/modules/core/src/tools/geometry/vpXmlParserRectOriented.cpp index 8aca50972f..ce0445330e 100644 --- a/modules/core/src/tools/geometry/vpXmlParserRectOriented.cpp +++ b/modules/core/src/tools/geometry/vpXmlParserRectOriented.cpp @@ -50,6 +50,10 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpXmlParserRectOriented::Impl { @@ -203,7 +207,9 @@ void vpXmlParserRectOriented::save(const std::string &filename, bool append) { m vpRectOriented vpXmlParserRectOriented::getRectangle() const { return m_impl->getRectangle(); } void vpXmlParserRectOriented::setRectangle(const vpRectOriented &rectangle) { m_impl->setRectangle(rectangle); } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpXmlParserRectOriented.cpp.o) has no symbols void dummy_vpXmlParserRectOriented() { }; diff --git a/modules/core/src/tools/histogram/vpHistogram.cpp b/modules/core/src/tools/histogram/vpHistogram.cpp index ff93dc2f48..4c793a6b95 100644 --- a/modules/core/src/tools/histogram/vpHistogram.cpp +++ b/modules/core/src/tools/histogram/vpHistogram.cpp @@ -47,6 +47,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif #if defined(VISP_HAVE_THREADS) #include @@ -1194,3 +1198,6 @@ bool vpHistogram::write(const char *filename) return true; } +#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 42804768f6..ce74255e0a 100644 --- a/modules/core/src/tools/histogram/vpHistogramPeak.cpp +++ b/modules/core/src/tools/histogram/vpHistogramPeak.cpp @@ -43,15 +43,19 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Default constructor for a gray level histogram peak. */ -vpHistogramPeak::vpHistogramPeak() : level(0), value(0) {} +vpHistogramPeak::vpHistogramPeak() : level(0), value(0) { } /*! Default constructor for a gray level histogram peak. */ -vpHistogramPeak::vpHistogramPeak(unsigned char lvl, unsigned val) : level(lvl), value(val) {} +vpHistogramPeak::vpHistogramPeak(unsigned char lvl, unsigned val) : level(lvl), value(val) { } /*! Copy constructor of a gray level histogram peak. @@ -96,7 +100,9 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &s, const vpHistogramPeak &p) 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 2a0f14f78f..e980cd4b94 100644 --- a/modules/core/src/tools/histogram/vpHistogramValey.cpp +++ b/modules/core/src/tools/histogram/vpHistogramValey.cpp @@ -43,6 +43,10 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Copy operator. @@ -84,7 +88,9 @@ VISP_EXPORT std::ostream &operator<<(std::ostream &s, const vpHistogramValey &v) return s; } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif /* * Local variables: * c-basic-offset: 2 diff --git a/modules/core/src/tools/time/vpTime.cpp b/modules/core/src/tools/time/vpTime.cpp index d4250259d8..be8c492df6 100644 --- a/modules/core/src/tools/time/vpTime.cpp +++ b/modules/core/src/tools/time/vpTime.cpp @@ -33,6 +33,11 @@ * *****************************************************************************/ +/*! + \file vpTime.cpp + \brief Time management and measurement +*/ + #include #include @@ -46,11 +51,6 @@ #define USE_CXX11_CHRONO 0 #endif -/*! - \file vpTime.cpp - \brief Time management and measurement -*/ - // Unix depend version #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX @@ -61,6 +61,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif #ifndef DOXYGEN_SHOULD_SKIP_THIS namespace vpTime { @@ -210,17 +214,17 @@ int wait(double t0, double t) "vpTime::wait() is not implemented on Windows Phone 8.0")); #endif #endif + } } -} -/*! - Wait t miliseconds from now. + /*! + Wait t miliseconds from now. - The waiting is done by a call to usleep() if the time to wait is greater - than vpTime::minTimeForUsleepCall. + The waiting is done by a call to usleep() if the time to wait is greater + than vpTime::minTimeForUsleepCall. - \param t : Time to wait in ms. -*/ + \param t : Time to wait in ms. + */ void wait(double t) { double timeToWait = t; @@ -261,14 +265,14 @@ void wait(double t) "vpTime::wait() is not implemented on Windows Phone 8.0")); #endif #endif + } } -} -/*! - Sleep t miliseconds from now. + /*! + Sleep t miliseconds from now. - \param t : Time to sleep in ms. -*/ + \param t : Time to sleep in ms. + */ void sleepMs(double t) { #if !defined(_WIN32) && (defined(__unix__) || defined(__unix) || (defined(__APPLE__) && defined(__MACH__))) // UNIX @@ -419,3 +423,6 @@ void vpChrono::stop() m_durationMs += vpTime::measureTimeMs() - m_lastTimePoint; #endif } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tracking/forward-projection/vpCircle.cpp b/modules/core/src/tracking/forward-projection/vpCircle.cpp index a5674ba4fa..e3b3c6805f 100644 --- a/modules/core/src/tracking/forward-projection/vpCircle.cpp +++ b/modules/core/src/tracking/forward-projection/vpCircle.cpp @@ -37,6 +37,10 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif void vpCircle::init() { oP.resize(7); @@ -432,3 +436,6 @@ void vpCircle::computeIntersectionPoint(const vpCircle &circle, const vpCameraPa (ctheta * n11 * Yg)) + (ctheta3 * n11 * Yg) + (ctheta * n02 * Xg)) - (ctheta3 * n02 * Xg)) / (((n20 * ctheta2) + (2.0 * n11 * stheta * ctheta) + n02) - (n02 * ctheta2)) / stheta); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tracking/forward-projection/vpForwardProjection.cpp b/modules/core/src/tracking/forward-projection/vpForwardProjection.cpp index 285008782e..cd9792d3c4 100644 --- a/modules/core/src/tracking/forward-projection/vpForwardProjection.cpp +++ b/modules/core/src/tracking/forward-projection/vpForwardProjection.cpp @@ -33,14 +33,18 @@ * *****************************************************************************/ -#include -#include - /*! \file vpForwardProjection.cpp \brief class that defines what is a point */ +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Print to stdout the feature parameters in: - the object frame @@ -101,3 +105,6 @@ void vpForwardProjection::project(const vpHomogeneousMatrix &cMo) */ void vpForwardProjection::track(const vpHomogeneousMatrix &cMo) { project(cMo); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tracking/forward-projection/vpLine.cpp b/modules/core/src/tracking/forward-projection/vpLine.cpp index 2d7a7113c3..b94db57cc5 100644 --- a/modules/core/src/tracking/forward-projection/vpLine.cpp +++ b/modules/core/src/tracking/forward-projection/vpLine.cpp @@ -33,6 +33,11 @@ * *****************************************************************************/ +/*! + \file vpLine.cpp + \brief class that defines what is a line +*/ + #include #include @@ -40,11 +45,10 @@ #include -/*! - \file vpLine.cpp - \brief class that defines what is a line -*/ - +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Initialize the memory space requested for the 2D line parameters (\e @@ -549,3 +553,6 @@ vpLine *vpLine::duplicate() const vpLine *feature = new vpLine(*this); return feature; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tracking/forward-projection/vpPoint.cpp b/modules/core/src/tracking/forward-projection/vpPoint.cpp index 2767575b43..a630200556 100644 --- a/modules/core/src/tracking/forward-projection/vpPoint.cpp +++ b/modules/core/src/tracking/forward-projection/vpPoint.cpp @@ -33,15 +33,19 @@ * *****************************************************************************/ -#include -#include -#include - /*! \file vpPoint.cpp \brief Class that defines what is a 3D point. */ +#include +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif void vpPoint::init() { p.resize(3); @@ -506,3 +510,6 @@ 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; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tracking/forward-projection/vpSphere.cpp b/modules/core/src/tracking/forward-projection/vpSphere.cpp index 1f892dd383..93185d70b9 100644 --- a/modules/core/src/tracking/forward-projection/vpSphere.cpp +++ b/modules/core/src/tracking/forward-projection/vpSphere.cpp @@ -36,6 +36,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * Initialize internal sphere parameters. */ @@ -297,3 +301,6 @@ void vpSphere::display(const vpImage &I, const vpCameraParameters &cam, { vpFeatureDisplay::displayEllipse(p[0], p[1], p[2], p[3], p[4], cam, I, color, thickness); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/core/src/tracking/vpTracker.cpp b/modules/core/src/tracking/vpTracker.cpp index e0ec1f0e6f..9562d74b8c 100644 --- a/modules/core/src/tracking/vpTracker.cpp +++ b/modules/core/src/tracking/vpTracker.cpp @@ -33,17 +33,22 @@ * *****************************************************************************/ -#include -#include - /*! \file vpTracker.cpp \brief Class that defines what is a generic tracker. */ +#include +#include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + void vpTracker::init() { cPAvailable = false; } -vpTracker::vpTracker() : p(), cP(), cPAvailable(false) {} +vpTracker::vpTracker() : p(), cP(), cPAvailable(false) { } vpTracker::vpTracker(const vpTracker &tracker) : p(), cP(), cPAvailable(false) { *this = tracker; } @@ -55,7 +60,9 @@ vpTracker &vpTracker::operator=(const vpTracker &tracker) return *this; } - +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif /* * Local variables: * c-basic-offset: 2 diff --git a/modules/detection/include/visp3/detection/vpDetectorAprilTag.h b/modules/detection/include/visp3/detection/vpDetectorAprilTag.h index 7169c5007b..8cb4ee8bd1 100644 --- a/modules/detection/include/visp3/detection/vpDetectorAprilTag.h +++ b/modules/detection/include/visp3/detection/vpDetectorAprilTag.h @@ -46,6 +46,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpDetectorAprilTag * \ingroup group_detection_tag @@ -418,5 +423,9 @@ inline std::ostream &operator<<(std::ostream &os, const vpDetectorAprilTag::vpAp return os; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif #endif diff --git a/modules/detection/include/visp3/detection/vpDetectorBase.h b/modules/detection/include/visp3/detection/vpDetectorBase.h index ceb1496a7c..19d663fae2 100644 --- a/modules/detection/include/visp3/detection/vpDetectorBase.h +++ b/modules/detection/include/visp3/detection/vpDetectorBase.h @@ -45,6 +45,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpDetectorBase * \ingroup group_detection_barcode group_detection_face @@ -131,4 +136,8 @@ class VISP_EXPORT vpDetectorBase //@} }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/detection/src/tag/vpDetectorAprilTag.cpp b/modules/detection/src/tag/vpDetectorAprilTag.cpp index eeea0d89b8..f06310baf5 100644 --- a/modules/detection/src/tag/vpDetectorAprilTag.cpp +++ b/modules/detection/src/tag/vpDetectorAprilTag.cpp @@ -60,6 +60,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #ifndef DOXYGEN_SHOULD_SKIP_THIS class vpDetectorAprilTag::Impl { @@ -1203,6 +1208,10 @@ void vpDetectorAprilTag::setZAlignedWithCameraAxis(bool zAlignedWithCameraFrame) m_impl->setZAlignedWithCameraAxis(zAlignedWithCameraFrame); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) // Work around to avoid warning: libvisp_core.a(vpDetectorAprilTag.cpp.o) has // no symbols diff --git a/modules/detection/src/vpDetectorBase.cpp b/modules/detection/src/vpDetectorBase.cpp index f69d44149f..a070e8380a 100644 --- a/modules/detection/src/vpDetectorBase.cpp +++ b/modules/detection/src/vpDetectorBase.cpp @@ -35,9 +35,13 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! - Default constructor. + Default constructor. */ vpDetectorBase::vpDetectorBase() : m_polygon(), m_message(), m_nb_objects(0), m_timeout_ms(0) { } @@ -120,3 +124,7 @@ vpRect vpDetectorBase::getBBox(size_t i) const vpRect roi(vpImagePoint(top, left), vpImagePoint(bottom, right)); return roi; } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/gui/include/visp3/gui/vpD3DRenderer.h b/modules/gui/include/visp3/gui/vpD3DRenderer.h index e3629d060c..38e4d17bb6 100644 --- a/modules/gui/include/visp3/gui/vpD3DRenderer.h +++ b/modules/gui/include/visp3/gui/vpD3DRenderer.h @@ -31,15 +31,14 @@ * D3D renderer for windows 32 display */ -#ifndef DOXYGEN_SHOULD_SKIP_THIS +#ifndef VPD3DRENDERER_HH +#define VPD3DRENDERER_HH #include +#ifndef DOXYGEN_SHOULD_SKIP_THIS #if (defined(VISP_HAVE_D3D9)) -#ifndef VPD3DRENDERER_HH -#define VPD3DRENDERER_HH - // Include WinSock2.h before windows.h to ensure that winsock.h is not // included by windows.h since winsock.h and winsock2.h are incompatible #include @@ -50,6 +49,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpD3DRenderer.h * @@ -189,5 +193,10 @@ class VISP_EXPORT vpD3DRenderer : public vpWin32Renderer unsigned int supPowerOf2(unsigned int n); }; #endif + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayD3D.h b/modules/gui/include/visp3/gui/vpDisplayD3D.h index b2cde98f8b..6b9318da08 100644 --- a/modules/gui/include/visp3/gui/vpDisplayD3D.h +++ b/modules/gui/include/visp3/gui/vpDisplayD3D.h @@ -31,15 +31,20 @@ * Windows 32 display using D3D */ -#include -#include -#if (defined(VISP_HAVE_D3D9)) - #ifndef VPDISPLAYD3D_HH #define VPDISPLAYD3D_HH +#include +#if (defined(VISP_HAVE_D3D9)) + +#include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpDisplayD3D * @@ -110,5 +115,9 @@ class VISP_EXPORT vpDisplayD3D : public vpDisplayWin32 vpScaleType type = SCALE_DEFAULT); }; + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayGDI.h b/modules/gui/include/visp3/gui/vpDisplayGDI.h index 83477dd799..a250f4a3dd 100644 --- a/modules/gui/include/visp3/gui/vpDisplayGDI.h +++ b/modules/gui/include/visp3/gui/vpDisplayGDI.h @@ -35,16 +35,23 @@ * Bruno Renier * *****************************************************************************/ -#include -#include -#if (defined(VISP_HAVE_GDI)) #ifndef vpDisplayGDI_HH #define vpDisplayGDI_HH +#include + +#if (defined(VISP_HAVE_GDI)) + +#include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpDisplayGDI * @@ -137,5 +144,8 @@ class VISP_EXPORT vpDisplayGDI : public vpDisplayWin32 vpScaleType type = SCALE_DEFAULT); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayGTK.h b/modules/gui/include/visp3/gui/vpDisplayGTK.h index ea4b093bc7..a32b26b578 100644 --- a/modules/gui/include/visp3/gui/vpDisplayGTK.h +++ b/modules/gui/include/visp3/gui/vpDisplayGTK.h @@ -40,6 +40,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \file vpDisplayGTK.h * \brief Define the GTK console to display images. @@ -228,5 +233,8 @@ class VISP_EXPORT vpDisplayGTK : public vpDisplay Impl *m_impl; }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h index 30d552c592..c3a5e76d96 100644 --- a/modules/gui/include/visp3/gui/vpDisplayOpenCV.h +++ b/modules/gui/include/visp3/gui/vpDisplayOpenCV.h @@ -47,6 +47,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \file vpDisplayOpenCV.h * \brief Define the OpenCV console to display images. @@ -262,5 +267,8 @@ class VISP_EXPORT vpDisplayOpenCV : public vpDisplay void overlay(std::function overlay_function, double opacity); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayWin32.h b/modules/gui/include/visp3/gui/vpDisplayWin32.h index 958a3fbd96..d2cc1a2d3c 100644 --- a/modules/gui/include/visp3/gui/vpDisplayWin32.h +++ b/modules/gui/include/visp3/gui/vpDisplayWin32.h @@ -31,13 +31,14 @@ * Windows 32 display base class */ -#include - -#if (defined(VISP_HAVE_GDI) || defined(VISP_HAVE_D3D9)) #ifndef vpDisplayWin32_hh #define vpDisplayWin32_hh +#include + +#if (defined(VISP_HAVE_GDI) || defined(VISP_HAVE_D3D9)) + #include #include @@ -51,6 +52,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #ifndef DOXYGEN_SHOULD_SKIP_THIS /*! * Used to pass parameters to the window's thread. @@ -187,5 +193,9 @@ class VISP_EXPORT vpDisplayWin32 : public vpDisplay void waitForInit(); }; + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpDisplayX.h b/modules/gui/include/visp3/gui/vpDisplayX.h index b7582422da..4482aae482 100644 --- a/modules/gui/include/visp3/gui/vpDisplayX.h +++ b/modules/gui/include/visp3/gui/vpDisplayX.h @@ -40,6 +40,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \file vpDisplayX.h * \brief Define the X11 console to display images. @@ -224,5 +229,8 @@ class VISP_EXPORT vpDisplayX : public vpDisplay Impl *m_impl; }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpGDIRenderer.h b/modules/gui/include/visp3/gui/vpGDIRenderer.h index ea195e1e9f..54d19d4703 100644 --- a/modules/gui/include/visp3/gui/vpGDIRenderer.h +++ b/modules/gui/include/visp3/gui/vpGDIRenderer.h @@ -36,12 +36,14 @@ * *****************************************************************************/ -#include -#if (defined(VISP_HAVE_GDI)) #ifndef vpGDIRenderer_HH #define vpGDIRenderer_HH +#include + +#if (defined(VISP_HAVE_GDI)) + #ifndef DOXYGEN_SHOULD_SKIP_THIS // Include WinSock2.h before windows.h to ensure that winsock.h is not @@ -56,6 +58,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + class VISP_EXPORT vpGDIRenderer : public vpWin32Renderer { // the handle of the associated window @@ -130,6 +137,10 @@ class VISP_EXPORT vpGDIRenderer : public vpWin32Renderer // converst a vpImage into a HBITMAP . void convertROI(const vpImage &I, const vpImagePoint &iP, unsigned int width, unsigned int height); }; + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpPlot.h b/modules/gui/include/visp3/gui/vpPlot.h index 1124417aeb..088025d02e 100644 --- a/modules/gui/include/visp3/gui/vpPlot.h +++ b/modules/gui/include/visp3/gui/vpPlot.h @@ -44,6 +44,12 @@ #include #if defined(VISP_HAVE_DISPLAY) + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpPlot * \ingroup group_gui_plotter @@ -192,6 +198,10 @@ class VISP_EXPORT vpPlot void initNbGraph(unsigned int nbGraph); void displayGrid(); }; + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpPlotCurve.h b/modules/gui/include/visp3/gui/vpPlotCurve.h index 51f2a868a8..f811c3cd7a 100644 --- a/modules/gui/include/visp3/gui/vpPlotCurve.h +++ b/modules/gui/include/visp3/gui/vpPlotCurve.h @@ -51,6 +51,11 @@ #if defined(VISP_HAVE_DISPLAY) +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + class vpPlotCurve { public: @@ -80,6 +85,10 @@ class vpPlotCurve void plotList(const vpImage &I, double xorg, double yorg, double zoomx, double zoomy); }; + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpPlotGraph.h b/modules/gui/include/visp3/gui/vpPlotGraph.h index 935e4c15f9..b87f052d8d 100644 --- a/modules/gui/include/visp3/gui/vpPlotGraph.h +++ b/modules/gui/include/visp3/gui/vpPlotGraph.h @@ -33,11 +33,13 @@ * *****************************************************************************/ -#ifndef DOXYGEN_SHOULD_SKIP_THIS - #ifndef vpPlotGraph_H #define vpPlotGraph_H +#include + +#ifndef DOXYGEN_SHOULD_SKIP_THIS + #include #include @@ -52,6 +54,11 @@ #if defined(VISP_HAVE_DISPLAY) +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + class vpPlotGraph { public: @@ -216,6 +223,10 @@ class vpPlotGraph void setUnitZ(const std::string &unitz); }; + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpProjectionDisplay.h b/modules/gui/include/visp3/gui/vpProjectionDisplay.h index 77adced801..4fcd663d80 100644 --- a/modules/gui/include/visp3/gui/vpProjectionDisplay.h +++ b/modules/gui/include/visp3/gui/vpProjectionDisplay.h @@ -57,6 +57,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! \class vpProjectionDisplay \ingroup group_gui_projection @@ -95,18 +100,18 @@ class VISP_EXPORT vpProjectionDisplay vpProjectionDisplay() : Icam(), Iext(), #if defined(VISP_HAVE_DISPLAY) - dIcam(), dIext(), + dIcam(), dIext(), #endif - listFp(), o(), x(), y(), z(), traj() + listFp(), o(), x(), y(), z(), traj() { init(); } explicit vpProjectionDisplay(int select) : Icam(), Iext(), #if defined(VISP_HAVE_DISPLAY) - dIcam(), dIext(), + dIcam(), dIext(), #endif - listFp(), o(), x(), y(), z(), traj() + listFp(), o(), x(), y(), z(), traj() { init(select); } @@ -127,11 +132,9 @@ class VISP_EXPORT vpProjectionDisplay vpMatrix traj; }; + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif - -/* - * Local variables: - * c-basic-offset: 2 - * End: - */ diff --git a/modules/gui/include/visp3/gui/vpWin32API.h b/modules/gui/include/visp3/gui/vpWin32API.h index fa11987a69..8d8c36a2b4 100644 --- a/modules/gui/include/visp3/gui/vpWin32API.h +++ b/modules/gui/include/visp3/gui/vpWin32API.h @@ -49,6 +49,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + DWORD vpProcessErrors(const std::string &api_name); void vpSelectObject(HWND hWnd, HDC hDC, HDC hDCMem, HGDIOBJ h); void vpPrepareImageWithPen(CRITICAL_SECTION *CriticalSection, HWND hWnd, HBITMAP bmp, COLORREF color, @@ -63,5 +68,9 @@ BOOL vpBitBlt(HDC hdcDest, int nXDest, int nYDest, int nWidth, int nHeight, HDC BOOL vpInvalidateRect(HWND hWnd, const RECT *lpRect, BOOL bErase); COLORREF vpSetPixel(HDC hdc, int X, int Y, COLORREF crColor); HBITMAP vpCreateBitmap(int nWidth, int nHeight, UINT cPlanes, UINT cBitsPerPel, const VOID *lpvBits); + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpWin32Renderer.h b/modules/gui/include/visp3/gui/vpWin32Renderer.h index b169c57b4f..90231c57ae 100644 --- a/modules/gui/include/visp3/gui/vpWin32Renderer.h +++ b/modules/gui/include/visp3/gui/vpWin32Renderer.h @@ -36,13 +36,14 @@ * *****************************************************************************/ -#include - -#if (defined(VISP_HAVE_GDI) || defined(VISP_HAVE_D3D9)) #ifndef vpWin32Renderer_HH #define vpWin32Renderer_HH +#include + +#if (defined(VISP_HAVE_GDI) || defined(VISP_HAVE_D3D9)) + #ifndef DOXYGEN_SHOULD_SKIP_THIS #include @@ -53,6 +54,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + class VISP_EXPORT vpWin32Renderer { @@ -63,9 +69,9 @@ class VISP_EXPORT vpWin32Renderer unsigned int m_rscale; public: - vpWin32Renderer() : m_rwidth(0), m_rheight(0), m_rscale(1){}; + vpWin32Renderer() : m_rwidth(0), m_rheight(0), m_rscale(1) { }; //! Destructor. - virtual ~vpWin32Renderer(){}; + virtual ~vpWin32Renderer() { }; //! Inits the display . virtual bool init(HWND hWnd, unsigned int w, unsigned int h) = 0; @@ -171,6 +177,10 @@ class VISP_EXPORT vpWin32Renderer virtual void getImage(vpImage &I) = 0; }; + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif #endif diff --git a/modules/gui/include/visp3/gui/vpWin32Window.h b/modules/gui/include/visp3/gui/vpWin32Window.h index 1e97ad6e0f..2b7c35863a 100644 --- a/modules/gui/include/visp3/gui/vpWin32Window.h +++ b/modules/gui/include/visp3/gui/vpWin32Window.h @@ -37,11 +37,12 @@ * *****************************************************************************/ +#ifndef vpWin32Window_HH +#define vpWin32Window_HH + #include #if (defined(VISP_HAVE_GDI) || defined(VISP_HAVE_D3D9)) -#ifndef vpWin32Window_HH -#define vpWin32Window_HH #ifndef DOXYGEN_SHOULD_SKIP_THIS @@ -54,6 +55,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + // ViSP-defined messages for window's callback function #define vpWM_GETCLICK WM_USER + 1 #define vpWM_DISPLAY WM_USER + 2 @@ -134,6 +140,9 @@ class VISP_EXPORT vpWin32Window friend LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #endif #endif diff --git a/modules/gui/src/display/vpDisplayGTK.cpp b/modules/gui/src/display/vpDisplayGTK.cpp index 8ce48e314b..19b4bda8f8 100644 --- a/modules/gui/src/display/vpDisplayGTK.cpp +++ b/modules/gui/src/display/vpDisplayGTK.cpp @@ -68,6 +68,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + class vpDisplayGTK::Impl { public: @@ -1588,7 +1593,11 @@ unsigned int vpDisplayGTK::getScreenHeight() return height; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayGTK.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpDisplayGTK.cpp.o) has no symbols void dummy_vpDisplayGTK() { }; #endif diff --git a/modules/gui/src/display/vpDisplayOpenCV.cpp b/modules/gui/src/display/vpDisplayOpenCV.cpp index 73f3a52d91..69b66b627f 100644 --- a/modules/gui/src/display/vpDisplayOpenCV.cpp +++ b/modules/gui/src/display/vpDisplayOpenCV.cpp @@ -65,6 +65,11 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #ifndef CV_RGB #define CV_RGB(r, g, b) cv::Scalar((b), (g), (r), 0) #endif @@ -1789,7 +1794,11 @@ void vpDisplayOpenCV::overlay(std::function overlay_function, d } } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayOpenCV.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpDisplayOpenCV.cpp.o) has no symbols void dummy_vpDisplayOpenCV() { }; #endif diff --git a/modules/gui/src/display/vpDisplayX.cpp b/modules/gui/src/display/vpDisplayX.cpp index 8f4517c4a0..7390c30073 100644 --- a/modules/gui/src/display/vpDisplayX.cpp +++ b/modules/gui/src/display/vpDisplayX.cpp @@ -66,6 +66,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + // Work around to use this class with Eigen3 #ifdef Success #undef Success // See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=253 @@ -2660,7 +2665,11 @@ bool vpDisplayX::getPointerPosition(vpImagePoint &ip) return ret; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayX.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpDisplayX.cpp.o) has no symbols void dummy_vpDisplayX() { }; #endif diff --git a/modules/gui/src/display/windows/vpD3DRenderer.cpp b/modules/gui/src/display/windows/vpD3DRenderer.cpp index 0ab06eb0e1..5f72aeb4a6 100644 --- a/modules/gui/src/display/windows/vpD3DRenderer.cpp +++ b/modules/gui/src/display/windows/vpD3DRenderer.cpp @@ -35,17 +35,23 @@ * Bruno Renier * *****************************************************************************/ -#ifndef DOXYGEN_SHOULD_SKIP_THIS #include #include + #if (defined(_WIN32) & defined(VISP_HAVE_D3D9)) +#ifndef DOXYGEN_SHOULD_SKIP_THIS #include #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /* Be careful, when using : @@ -1190,8 +1196,12 @@ void vpD3DRenderer::getImage(vpImage &I) } } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpD3DRenderer.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpD3DRenderer.cpp.o) has no symbols void dummy_vpD3DRenderer() { }; #endif #endif diff --git a/modules/gui/src/display/windows/vpDisplayD3D.cpp b/modules/gui/src/display/windows/vpDisplayD3D.cpp index 2d13fb9151..60914444c0 100644 --- a/modules/gui/src/display/windows/vpDisplayD3D.cpp +++ b/modules/gui/src/display/windows/vpDisplayD3D.cpp @@ -47,6 +47,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! \brief Basic constructor. */ @@ -188,7 +192,11 @@ vpDisplayD3D::vpDisplayD3D(vpImage &I, int winx, int winy, const init(I, winx, winy, title); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayD3D.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpDisplayD3D.cpp.o) has no symbols void dummy_vpDisplayD3D() { }; #endif diff --git a/modules/gui/src/display/windows/vpDisplayGDI.cpp b/modules/gui/src/display/windows/vpDisplayGDI.cpp index b96086d321..048ebe993a 100644 --- a/modules/gui/src/display/windows/vpDisplayGDI.cpp +++ b/modules/gui/src/display/windows/vpDisplayGDI.cpp @@ -46,6 +46,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + // A vpDisplayGDI is just a vpDisplayWin32 which uses a vpGDIRenderer to do // the drawing. @@ -188,7 +193,11 @@ vpDisplayGDI::vpDisplayGDI(vpImage &I, int winx, int winy, const init(I, winx, winy, title); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayGDI.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpDisplayGDI.cpp.o) has no symbols void dummy_vpDisplayGDI() { }; #endif diff --git a/modules/gui/src/display/windows/vpDisplayWin32.cpp b/modules/gui/src/display/windows/vpDisplayWin32.cpp index 551fe65770..6c73236e57 100644 --- a/modules/gui/src/display/windows/vpDisplayWin32.cpp +++ b/modules/gui/src/display/windows/vpDisplayWin32.cpp @@ -43,6 +43,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + const int vpDisplayWin32::MAX_INIT_DELAY = 5000; /*! @@ -919,7 +924,12 @@ unsigned int vpDisplayWin32::getScreenHeight() getScreenSize(width, height); return height; } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpDisplayWin32.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpDisplayWin32.cpp.o) has no symbols void dummy_vpDisplayWin32() { }; #endif diff --git a/modules/gui/src/display/windows/vpGDIRenderer.cpp b/modules/gui/src/display/windows/vpGDIRenderer.cpp index cea70d073f..b82667120c 100644 --- a/modules/gui/src/display/windows/vpGDIRenderer.cpp +++ b/modules/gui/src/display/windows/vpGDIRenderer.cpp @@ -44,6 +44,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! Constructor. */ @@ -1027,8 +1032,12 @@ void vpGDIRenderer::getImage(vpImage &I) delete[] imBuffer; } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpGDIRenderer.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpGDIRenderer.cpp.o) has no symbols void dummy_vpGDIRenderer() { }; #endif diff --git a/modules/gui/src/display/windows/vpWin32API.cpp b/modules/gui/src/display/windows/vpWin32API.cpp index ca65e445bd..27d5d66637 100644 --- a/modules/gui/src/display/windows/vpWin32API.cpp +++ b/modules/gui/src/display/windows/vpWin32API.cpp @@ -42,6 +42,12 @@ #if (defined(VISP_HAVE_GDI) || defined(VISP_HAVE_D3D9)) #include #include + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + DWORD vpProcessErrors(const std::string &api_name) { LPVOID lpMsgBuf; @@ -135,7 +141,11 @@ HBITMAP vpCreateBitmap(int nWidth, int nHeight, UINT cPlanes, UINT cBitsPerPel, return ret; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpWin32API.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpWin32API.cpp.o) has no symbols void dummy_vpWin32API() { }; #endif diff --git a/modules/gui/src/display/windows/vpWin32Window.cpp b/modules/gui/src/display/windows/vpWin32Window.cpp index 2dd7d3c0d4..9102b6327a 100644 --- a/modules/gui/src/display/windows/vpWin32Window.cpp +++ b/modules/gui/src/display/windows/vpWin32Window.cpp @@ -48,6 +48,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + // Should be already defined ... #ifndef GET_X_LPARAM #define GET_X_LPARAM(lp) ((int)(short)LOWORD(lp)) @@ -311,8 +316,12 @@ void vpWin32Window::initWindow(const char *title, int posx, int posy, unsigned i } } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpWin32Window.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpWin32Window.cpp.o) has no symbols void dummy_vpWin32Window() { }; #endif diff --git a/modules/gui/src/forward-projection/vpProjectionDisplay.cpp b/modules/gui/src/forward-projection/vpProjectionDisplay.cpp index 39d0db1553..e912f04d14 100644 --- a/modules/gui/src/forward-projection/vpProjectionDisplay.cpp +++ b/modules/gui/src/forward-projection/vpProjectionDisplay.cpp @@ -57,6 +57,11 @@ //#include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + void vpProjectionDisplay::insert(vpForwardProjection &fp) { // vpForwardProjection *f ; @@ -88,7 +93,7 @@ void vpProjectionDisplay::init(const int select) init(); } -void vpProjectionDisplay::close() {} +void vpProjectionDisplay::close() { } void vpProjectionDisplay::display(vpImage &I, const vpHomogeneousMatrix &cextMo, const vpHomogeneousMatrix &cMo, const vpCameraParameters &cam, const vpColor &color, @@ -145,8 +150,12 @@ void vpProjectionDisplay::displayCamera(vpImage &I, const vpHomog vpDisplay::displayArrow(I, ipo, ip, vpColor::blue, 4 + thickness, 2 + thickness, thickness); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpProjectionDisplay.cpp.o) +// Work around to avoid warning: libvisp_gui.a(vpProjectionDisplay.cpp.o) // has no symbols -void dummy_vpProjectionDisplay(){}; +void dummy_vpProjectionDisplay() { }; #endif diff --git a/modules/gui/src/plot/vpPlot.cpp b/modules/gui/src/plot/vpPlot.cpp index da074c1a12..f4ff388c93 100644 --- a/modules/gui/src/plot/vpPlot.cpp +++ b/modules/gui/src/plot/vpPlot.cpp @@ -49,6 +49,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! Default constructor. @@ -727,7 +732,11 @@ void vpPlot::saveData(unsigned int graphNum, const std::string &dataFile, const fichier.close(); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpPlot.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpPlot.cpp.o) has no symbols void dummy_vpPlot() { }; #endif diff --git a/modules/gui/src/plot/vpPlotCurve.cpp b/modules/gui/src/plot/vpPlotCurve.cpp index ea4c221f73..98402c0ebb 100644 --- a/modules/gui/src/plot/vpPlotCurve.cpp +++ b/modules/gui/src/plot/vpPlotCurve.cpp @@ -44,6 +44,12 @@ #include #if defined(VISP_HAVE_DISPLAY) + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + vpPlotCurve::vpPlotCurve() : color(vpColor::red), curveStyle(point), thickness(1), nbPoint(0), lastPoint(), pointListx(), pointListy(), pointListz(), legend(), xmin(0), xmax(0), ymin(0), ymax(0) @@ -114,8 +120,12 @@ void vpPlotCurve::plotList(const vpImage &I, double xorg, double } } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpPlotCurve.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpPlotCurve.cpp.o) has no symbols void dummy_vpPlotCurve() { }; #endif #endif diff --git a/modules/gui/src/plot/vpPlotGraph.cpp b/modules/gui/src/plot/vpPlotGraph.cpp index 40f68ff083..b543224bbc 100644 --- a/modules/gui/src/plot/vpPlotGraph.cpp +++ b/modules/gui/src/plot/vpPlotGraph.cpp @@ -54,6 +54,11 @@ #if defined(VISP_HAVE_DISPLAY) +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + int laFonctionSansNom(double delta); void getGrid3DPoint(double pente, vpImagePoint &iPunit, vpImagePoint &ip1, vpImagePoint &ip2, vpImagePoint &ip3); @@ -1338,8 +1343,12 @@ vpHomogeneousMatrix vpPlotGraph::navigation(const vpImage &I, boo return mov; } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #elif !defined(VISP_BUILD_SHARED_LIBS) -// Work around to avoid warning: libvisp_core.a(vpPlotGraph.cpp.o) has no symbols +// Work around to avoid warning: libvisp_gui.a(vpPlotGraph.cpp.o) has no symbols void dummy_vpPlotGraph() { }; #endif #endif diff --git a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h index d006d836c4..97dd15945a 100644 --- a/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h +++ b/modules/imgproc/include/visp3/imgproc/vpCircleHoughTransform.h @@ -51,6 +51,11 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /** * \ingroup group_hough_transform * \brief Class that permits to detect 2D circles in a image using @@ -1281,4 +1286,9 @@ class VISP_EXPORT vpCircleHoughTransform std::vector m_finalCircleVotes; /*!< Number of votes for the final circles.*/ std::vector > > m_finalCirclesVotingPoints; /*!< Points that voted for each final circle.*/ }; + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/imgproc/include/visp3/imgproc/vpContours.h b/modules/imgproc/include/visp3/imgproc/vpContours.h index 8531f0c0f0..743ff1952b 100644 --- a/modules/imgproc/include/visp3/imgproc/vpContours.h +++ b/modules/imgproc/include/visp3/imgproc/vpContours.h @@ -74,9 +74,13 @@ #include #include - -namespace +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +namespace vp +#else +namespace visp +#endif { + /*! * Possible directions to find a contour. */ @@ -141,7 +145,7 @@ struct vpDirection { vpDirection direction; int directionSize = LAST_DIRECTION; - direction.m_direction = vpDirectionType(((int)m_direction + 1) % directionSize); + direction.m_direction = vpDirectionType((static_cast(m_direction) + 1) % directionSize); return direction; } @@ -153,8 +157,8 @@ struct vpDirection vpDirection counterClockwise() { vpDirection direction; - int directionSize = (int)LAST_DIRECTION; - int idx = vpMath::modulo((int)m_direction - 1, directionSize); + int directionSize = static_cast(LAST_DIRECTION); + int idx = vpMath::modulo(static_cast(m_direction) - 1, directionSize); direction.m_direction = vpDirectionType(idx); return direction; @@ -168,10 +172,10 @@ struct vpDirection */ vpImagePoint active(const vpImage &I, const vpImagePoint &point) { - int yy = (int)(point.get_i() + m_diry[(int)m_direction]); - int xx = (int)(point.get_j() + m_dirx[(int)m_direction]); + int yy = static_cast(point.get_i() + m_diry[static_cast(m_direction)]); + int xx = static_cast(point.get_j() + m_dirx[static_cast(m_direction)]); - if (xx < 0 || xx >= (int)I.getWidth() || yy < 0 || yy >= (int)I.getHeight()) { + if ((xx < 0) || (xx >= static_cast(I.getWidth())) || (yy < 0) || (yy >= static_cast(I.getHeight()))) { return vpImagePoint(-1, -1); } @@ -179,10 +183,7 @@ struct vpDirection return pixel != 0 ? vpImagePoint(yy, xx) : vpImagePoint(-1, -1); } }; -} // namespace -namespace vp -{ /*! * Type of contour. */ @@ -220,12 +221,12 @@ struct vpContour /*! * Default constructor. */ - vpContour() : m_children(), m_contourType(vp::CONTOUR_HOLE), m_parent(nullptr), m_points() { } + vpContour() : m_children(), m_contourType(CONTOUR_HOLE), m_parent(nullptr), m_points() { } /*! * Constructor of a given contour type. */ - vpContour(const vpContourType &type) : m_children(), m_contourType(type), m_parent(nullptr), m_points() { } + explicit vpContour(const vpContourType &type) : m_children(), m_contourType(type), m_parent(nullptr), m_points() { } /*! * Copy constructor. @@ -235,7 +236,8 @@ struct vpContour { // Copy the underlying contours - for (std::vector::const_iterator it = contour.m_children.begin(); it != contour.m_children.end(); + std::vector::const_iterator contour_m_children_end = contour.m_children.end(); + for (std::vector::const_iterator it = contour.m_children.begin(); it != contour_m_children_end; ++it) { vpContour *copy = new vpContour(**it); copy->m_parent = this; @@ -248,7 +250,8 @@ struct vpContour */ virtual ~vpContour() { - for (std::vector::iterator it = m_children.begin(); it != m_children.end(); ++it) { + std::vector::iterator m_children_end = m_children.end(); + for (std::vector::iterator it = m_children.begin(); it != m_children_end; ++it) { (*it)->m_parent = nullptr; if (*it != nullptr) { delete *it; @@ -266,7 +269,8 @@ struct vpContour if (m_parent == nullptr) { // We are a root or an uninitialized contour so delete everything - for (std::vector::iterator it = m_children.begin(); it != m_children.end(); ++it) { + std::vector::iterator m_children_end = m_children.end(); + for (std::vector::iterator it = m_children.begin(); it != m_children_end; ++it) { (*it)->m_parent = nullptr; if (*it != nullptr) { delete *it; @@ -281,7 +285,8 @@ struct vpContour } m_children.clear(); - for (std::vector::const_iterator it = other.m_children.begin(); it != other.m_children.end(); ++it) { + std::vector::const_iterator other_m_children_end = other.m_children.end(); + for (std::vector::const_iterator it = other.m_children.begin(); it != other_m_children_end; ++it) { vpContour *copy = new vpContour(**it); copy->m_parent = this; m_children.push_back(copy); @@ -340,7 +345,8 @@ VISP_EXPORT void drawContours(vpImage &I, const std::vector &I_original, vpContour &contours, std::vector > &contourPts, - const vpContourRetrievalType &retrievalMode = vp::CONTOUR_RETR_TREE); -} // namespace vp + const vpContourRetrievalType &retrievalMode = CONTOUR_RETR_TREE); + +} // namespace #endif diff --git a/modules/imgproc/include/visp3/imgproc/vpImgproc.h b/modules/imgproc/include/visp3/imgproc/vpImgproc.h index 45997739fe..a2c315ac5f 100644 --- a/modules/imgproc/include/visp3/imgproc/vpImgproc.h +++ b/modules/imgproc/include/visp3/imgproc/vpImgproc.h @@ -45,10 +45,17 @@ #include #include -#define USE_OLD_FILL_HOLE 0 +#ifdef VISP_BUILD_DEPRECATED_FUNCTIONS +#define VISP_IMGPROC_NAMESPACE vp +#else +#define VISP_IMGPROC_NAMESPACE visp +#endif -namespace vp +namespace VISP_IMGPROC_NAMESPACE { + +#define USE_OLD_FILL_HOLE 0 + /*! * Retinex level that allows to specifies distribution * of the Gaussian blurring kernel sizes for scale division values > 2. @@ -126,7 +133,7 @@ VISP_EXPORT std::string vpGammaMethodList(const std::string &pref = "<", const s const std::string &suf = ">"); /** - * \brief Cast a \b vp::vpGammaMethod into a string, to know its name. + * \brief Cast a \b vpGammaMethod into a string, to know its name. * * \param[in] type The type that must be casted into a string. * \return std::string The corresponding name. @@ -134,10 +141,10 @@ VISP_EXPORT std::string vpGammaMethodList(const std::string &pref = "<", const s VISP_EXPORT std::string vpGammaMethodToString(const vpGammaMethod &type); /** - * \brief Cast a string into a \b vp::vpGammaMethod. + * \brief Cast a string into a \b vpGammaMethod. * * \param[in] name The name of the backend. - * \return vp::vpGammaMethod The corresponding enumeration value. + * \return vpGammaMethod The corresponding enumeration value. */ VISP_EXPORT vpGammaMethod vpGammaMethodFromString(const std::string &name); @@ -164,7 +171,7 @@ VISP_EXPORT std::string vpGammaColorHandlingList(const std::string &pref = "<", const std::string &suf = ">"); /** - * \brief Cast a \b vp::vpGammaColorHandling into a string, to know its name. + * \brief Cast a \b vpGammaColorHandling into a string, to know its name. * * \param[in] type The type that must be casted into a string. * \return std::string The corresponding name. @@ -172,10 +179,10 @@ VISP_EXPORT std::string vpGammaColorHandlingList(const std::string &pref = "<", VISP_EXPORT std::string vpGammaColorHandlingToString(const vpGammaColorHandling &type); /** - * \brief Cast a string into a \b vp::vpGammaColorHandling. + * \brief Cast a string into a \b vpGammaColorHandling. * * \param[in] name The name of the backend. - * \return vp::vpGammaColorHandling The corresponding enumeration value. + * \return vpGammaColorHandling The corresponding enumeration value. */ VISP_EXPORT vpGammaColorHandling vpGammaColorHandlingFromString(const std::string &name); @@ -363,7 +370,7 @@ VISP_EXPORT void equalizeHistogram(const vpImage &I1, vpImage &I * \param[in] p_mask : If different from nullptr, permits to indicate which points must be taken into account by setting * them to true. */ -VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, const vpGammaMethod &method = vp::GAMMA_MANUAL, +VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, const vpGammaMethod &method = GAMMA_MANUAL, const vpImage *p_mask = nullptr); /*! @@ -383,7 +390,7 @@ VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, * them to true. */ VISP_EXPORT void gammaCorrection(const vpImage &I1, vpImage &I2, const float &gamma, - const vpGammaMethod &method = vp::GAMMA_MANUAL, const vpImage *p_mask = nullptr); + const vpGammaMethod &method = GAMMA_MANUAL, const vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_gamma @@ -398,8 +405,8 @@ VISP_EXPORT void gammaCorrection(const vpImage &I1, vpImage &I, const float &gamma, const vpGammaColorHandling &colorHandling = vp::GAMMA_RGB, - const vpGammaMethod &method = vp::GAMMA_MANUAL, const vpImage *p_mask = nullptr); +VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, const vpGammaColorHandling &colorHandling = GAMMA_RGB, + const vpGammaMethod &method = GAMMA_MANUAL, const vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_gamma @@ -416,8 +423,8 @@ VISP_EXPORT void gammaCorrection(vpImage &I, const float &gamma, const v * them to true. */ VISP_EXPORT void gammaCorrection(const vpImage &I1, vpImage &I2, const float &gamma, - const vpGammaColorHandling &colorHandling = vp::GAMMA_RGB, - const vpGammaMethod &method = vp::GAMMA_MANUAL, const vpImage *p_mask = nullptr); + const vpGammaColorHandling &colorHandling = GAMMA_RGB, + const vpGammaMethod &method = GAMMA_MANUAL, const vpImage *p_mask = nullptr); /*! * \ingroup group_imgproc_retinex @@ -648,9 +655,10 @@ VISP_EXPORT void reconstruct(const vpImage &marker, const vpImage * \param backgroundValue : Value to set to the background. * \param foregroundValue : Value to set to the foreground. */ -VISP_EXPORT unsigned char autoThreshold(vpImage &I, const vp::vpAutoThresholdMethod &method, +VISP_EXPORT unsigned char autoThreshold(vpImage &I, const vpAutoThresholdMethod &method, const unsigned char backgroundValue = 0, const unsigned char foregroundValue = 255); -} // namespace vp + +} // namespace #endif diff --git a/modules/imgproc/src/vpCLAHE.cpp b/modules/imgproc/src/vpCLAHE.cpp index 5bea19d052..38ff57d97a 100644 --- a/modules/imgproc/src/vpCLAHE.cpp +++ b/modules/imgproc/src/vpCLAHE.cpp @@ -79,8 +79,13 @@ #include #include -namespace +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +namespace vp +#else +namespace visp +#endif { + int fastRound(float value) { return static_cast(value + 0.5f); } void clipHistogram(const std::vector &hist, std::vector &clippedHist, int limit) @@ -191,10 +196,7 @@ float transferValue(int v, const std::vector &hist, std::vector &clipp return transferValue(v, clippedHist); } -} // namespace -namespace vp -{ void clahe(const vpImage &I1, vpImage &I2, int blockRadius, int bins, float slope, bool fast) { if (blockRadius < 0) { @@ -481,4 +483,5 @@ void clahe(const vpImage &I1, vpImage &I2, int blockRadius, int ++cpt; } } -}; + +} // namespace diff --git a/modules/imgproc/src/vpCircleHoughTransform.cpp b/modules/imgproc/src/vpCircleHoughTransform.cpp index e88fa70ff7..ecc7fb43a1 100644 --- a/modules/imgproc/src/vpCircleHoughTransform.cpp +++ b/modules/imgproc/src/vpCircleHoughTransform.cpp @@ -33,13 +33,16 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + // Static variables const unsigned char vpCircleHoughTransform::edgeMapOn = 255; const unsigned char vpCircleHoughTransform::edgeMapOff = 0; #if (VISP_CXX_STANDARD == VISP_CXX_STANDARD_98) -namespace -{ // Sorting by decreasing probabilities bool hasBetterProba(std::pair a, std::pair b) { @@ -92,7 +95,6 @@ scaleFilter(vpArray2D &filter, const float &scale) } } } -}; #endif vpCircleHoughTransform::vpCircleHoughTransform() @@ -1203,3 +1205,7 @@ operator<<(std::ostream &os, const vpCircleHoughTransform &detector) os << detector.toString(); return os; } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/imgproc/src/vpConnectedComponents.cpp b/modules/imgproc/src/vpConnectedComponents.cpp index be93d2e98e..aa0adb3f3b 100644 --- a/modules/imgproc/src/vpConnectedComponents.cpp +++ b/modules/imgproc/src/vpConnectedComponents.cpp @@ -39,8 +39,13 @@ #include #include -namespace +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +namespace vp +#else +namespace visp +#endif { + void getNeighbors(const vpImage &I, std::queue &listOfNeighbors, unsigned int i, unsigned int j, const vpImageMorphology::vpConnexityType &connexity) { @@ -100,10 +105,7 @@ void visitNeighbors(vpImage &I_copy, std::queue &li } } } -} // namespace -namespace vp -{ void connectedComponents(const vpImage &I, vpImage &labels, int &nbComponents, const vpImageMorphology::vpConnexityType &connexity) { if (I.getSize() == 0) { @@ -161,4 +163,5 @@ void connectedComponents(const vpImage &I, vpImage &labels, nbComponents = current_label - 1; } -}; + +} // namespace diff --git a/modules/imgproc/src/vpContours.cpp b/modules/imgproc/src/vpContours.cpp index b982b3669b..0a195f0208 100644 --- a/modules/imgproc/src/vpContours.cpp +++ b/modules/imgproc/src/vpContours.cpp @@ -70,8 +70,13 @@ #include #include -namespace +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +namespace vp +#else +namespace visp +#endif { + bool fromTo(const vpImagePoint &from, const vpImagePoint &to, vpDirection &direction) { if (from == to) { @@ -131,7 +136,7 @@ bool crossesEastBorder(const vpImage &I, bool checked[8], const vpImagePoin return (I[i][j] != 0) && ((static_cast(point.get_j()) == (I.getWidth() - 1)) || b); } -void addContourPoint(vpImage &I, vp::vpContour *border, const vpImagePoint &point, bool checked[8], int nbd) +void addContourPoint(vpImage &I, vpContour *border, const vpImagePoint &point, bool checked[8], int nbd) { border->m_points.push_back(vpImagePoint(point.get_i() - 1, point.get_j() - 1)); // remove 1-pixel padding @@ -147,7 +152,7 @@ void addContourPoint(vpImage &I, vp::vpContour *border, const vpImagePoint } // Otherwise leave it alone } -void followBorder(vpImage &I, const vpImagePoint &ij, vpImagePoint &i2j2, vp::vpContour *border, int nbd) +void followBorder(vpImage &I, const vpImagePoint &ij, vpImagePoint &i2j2, vpContour *border, int nbd) { vpDirection dir; if (!fromTo(ij, i2j2, dir)) { @@ -234,25 +239,22 @@ bool isHoleBorderStart(const vpImage &I, unsigned int i, unsigned int j) return ((I[i][j] >= 1) && ((j == (I.getWidth() - 1)) || (I[i][j + 1] == 0))); } -void getContoursList(const vp::vpContour &root, int level, vp::vpContour &contour_list) +void getContoursList(const vpContour &root, int level, vpContour &contour_list) { if ((level > 0) && (level < std::numeric_limits::max())) { - vp::vpContour *contour_node = new vp::vpContour; + vpContour *contour_node = new vpContour; contour_node->m_contourType = root.m_contourType; contour_node->m_points = root.m_points; contour_list.m_children.push_back(contour_node); } - std::vector::const_iterator root_m_children_end = root.m_children.end(); - for (std::vector::const_iterator it = root.m_children.begin(); it != root_m_children_end; ++it) { + std::vector::const_iterator root_m_children_end = root.m_children.end(); + for (std::vector::const_iterator it = root.m_children.begin(); it != root_m_children_end; ++it) { getContoursList(**it, level + 1, contour_list); } } -} // namespace -namespace vp -{ void drawContours(vpImage &I, const std::vector > &contours, unsigned char grayValue) { if (I.getSize() == 0) { @@ -325,7 +327,7 @@ void findContours(const vpImage &I_original, vpContour &contours, // Background contour // By default the root contour is a hole contour - vpContour *root = new vpContour(vp::CONTOUR_HOLE); + vpContour *root = new vpContour(CONTOUR_HOLE); std::map borderMap; borderMap[lnbd] = root; @@ -348,16 +350,16 @@ void findContours(const vpImage &I_original, vpContour &contours, //(1) (a) ++nbd; from.set_j(from.get_j() - 1); - border->m_contourType = vp::CONTOUR_OUTER; + border->m_contourType = CONTOUR_OUTER; borderPrime = borderMap[lnbd]; // Table 1 switch (borderPrime->m_contourType) { - case vp::CONTOUR_OUTER: + case CONTOUR_OUTER: border->setParent(borderPrime->m_parent); break; - case vp::CONTOUR_HOLE: + case CONTOUR_HOLE: border->setParent(borderPrime); break; @@ -375,15 +377,15 @@ void findContours(const vpImage &I_original, vpContour &contours, borderPrime = borderMap[lnbd]; from.set_j(from.get_j() + 1); - border->m_contourType = vp::CONTOUR_HOLE; + border->m_contourType = CONTOUR_HOLE; // Table 1 switch (borderPrime->m_contourType) { - case vp::CONTOUR_OUTER: + case CONTOUR_OUTER: border->setParent(borderPrime); break; - case vp::CONTOUR_HOLE: + case CONTOUR_HOLE: border->setParent(borderPrime->m_parent); break; @@ -469,4 +471,5 @@ void findContours(const vpImage &I_original, vpContour &contours, delete root; root = nullptr; } -}; + +} // namespace diff --git a/modules/imgproc/src/vpFloodFill.cpp b/modules/imgproc/src/vpFloodFill.cpp index 34cf9c037f..368b8e2a88 100644 --- a/modules/imgproc/src/vpFloodFill.cpp +++ b/modules/imgproc/src/vpFloodFill.cpp @@ -66,8 +66,13 @@ #include #include +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) namespace vp +#else +namespace visp +#endif { + void floodFill(vpImage &I, const vpImagePoint &seedPoint, const unsigned char oldValue, const unsigned char newValue, const vpImageMorphology::vpConnexityType &connexity) { @@ -159,4 +164,5 @@ void floodFill(vpImage &I, const vpImagePoint &seedPoint, const u } } } -}; + +} // namespace diff --git a/modules/imgproc/src/vpImgproc.cpp b/modules/imgproc/src/vpImgproc.cpp index ff25389262..91ebeb8f9c 100644 --- a/modules/imgproc/src/vpImgproc.cpp +++ b/modules/imgproc/src/vpImgproc.cpp @@ -64,8 +64,9 @@ #include #include -namespace vp +namespace VISP_IMGPROC_NAMESPACE { + std::string vpGammaMethodList(const std::string &pref, const std::string &sep, const std::string &suf) { std::string list(pref); @@ -87,22 +88,22 @@ std::string vpGammaMethodToString(const vpGammaMethod &type) case GAMMA_MANUAL: name = "gamma_manual"; break; - case GAMMA_LOG_BASED: + case GAMMA_LOG_BASED: name = "gamma_log"; break; - case GAMMA_NONLINEAR_BASED: + case GAMMA_NONLINEAR_BASED: name = "gamma_nonlinear"; break; - case GAMMA_CDF_BASED: + case GAMMA_CDF_BASED: name = "gamma_cdf"; break; - case GAMMA_CLASSIFICATION_BASED: + case GAMMA_CLASSIFICATION_BASED: name = "gamma_classification"; break; - case GAMMA_SPATIAL_VARIANT_BASED: + case GAMMA_SPATIAL_VARIANT_BASED: name = "gamma_spatial_variant"; break; - case GAMMA_METHOD_COUNT: + case GAMMA_METHOD_COUNT: default: name = "gamma_method_unknown"; } @@ -144,13 +145,13 @@ std::string vpGammaColorHandlingToString(const vpGammaColorHandling &type) { std::string name; switch (type) { - case GAMMA_RGB: + case GAMMA_RGB: name = "gamma_color_rgb"; break; - case GAMMA_HSV: + case GAMMA_HSV: name = "gamma_color_hsv"; break; - case GAMMA_COLOR_HANDLING_COUNT: + case GAMMA_COLOR_HANDLING_COUNT: default: name = "gamma_color_unknown"; } @@ -191,7 +192,7 @@ void adjust(const vpImage &I1, vpImage &I2, double // Copy I1 to I2 I2 = I1; - vp::adjust(I2, alpha, beta); + adjust(I2, alpha, beta); } void adjust(vpImage &I, double alpha, double beta) @@ -214,13 +215,13 @@ void adjust(const vpImage &I1, vpImage &I2, double alpha, double // Copy I1 to I2 I2 = I1; - vp::adjust(I2, alpha, beta); + adjust(I2, alpha, beta); } void equalizeHistogram(vpImage &I, const vpImage *p_mask) { vpImage Icpy = I; - vp::equalizeHistogram(Icpy, I, p_mask); + equalizeHistogram(Icpy, I, p_mask); } void equalizeHistogram(const vpImage &I1, vpImage &I2, @@ -252,11 +253,11 @@ void equalizeHistogram(vpImage &I, bool useHSV) vpImageConvert::split(I, &pR, &pG, &pB, &pa); // Apply histogram equalization for each channel - vp::equalizeHistogram(pR); - vp::equalizeHistogram(pG); - vp::equalizeHistogram(pB); + equalizeHistogram(pR); + equalizeHistogram(pG); + equalizeHistogram(pB); - // Merge the result in I + // Merge the result in I unsigned int size = I.getWidth() * I.getHeight(); unsigned char *ptrStart = reinterpret_cast(I.bitmap); unsigned char *ptrEnd = ptrStart + (size * 4); @@ -290,9 +291,9 @@ void equalizeHistogram(vpImage &I, bool useHSV) reinterpret_cast(saturation.bitmap), reinterpret_cast(value.bitmap), size); // Histogram equalization on the value plane - vp::equalizeHistogram(value); + equalizeHistogram(value); - // Convert from HSV to RGBa + // Convert from HSV to RGBa vpImageConvert::HSVToRGBa(reinterpret_cast(hue.bitmap), reinterpret_cast(saturation.bitmap), reinterpret_cast(value.bitmap), reinterpret_cast(I.bitmap), size); } @@ -301,11 +302,9 @@ void equalizeHistogram(vpImage &I, bool useHSV) void equalizeHistogram(const vpImage &I1, vpImage &I2, bool useHSV) { I2 = I1; - vp::equalizeHistogram(I2, useHSV); + equalizeHistogram(I2, useHSV); } -namespace -{ /** * \brief This method is an implementation of the article "Towards Real-time Hardware Gamma Correction * for Dynamic Contrast Enhancement" by Jesse Scott, Michael Pusateri, IEEE Applied Imagery Pattern Recognition @@ -596,12 +595,11 @@ void gammaCorrectionSpatialBased(vpImage &I, const vpImage *p_mask } } } -} void gammaCorrection(vpImage &I, const float &gamma, const vpGammaMethod &method, const vpImage *p_mask) { float inverse_gamma = 1.0; - if ((gamma > 0) && (method == GAMMA_MANUAL)) { + if ((gamma > 0) && (method == GAMMA_MANUAL)) { inverse_gamma = 1.0f / gamma; // Construct the look-up table unsigned char lut[256]; @@ -611,7 +609,7 @@ void gammaCorrection(vpImage &I, const float &gamma, const vpGamm I.performLut(lut); } - else if (method == GAMMA_MANUAL) { + else if (method == GAMMA_MANUAL) { std::stringstream errMsg; errMsg << "ERROR: gamma correction factor ("; errMsg << gamma << ") cannot be negative when using a constant user-defined factor." << std::endl; @@ -623,19 +621,19 @@ void gammaCorrection(vpImage &I, const float &gamma, const vpGamm throw(vpException(vpException::badValue, errMsg.str())); } else { - if (method == GAMMA_NONLINEAR_BASED) { + if (method == GAMMA_NONLINEAR_BASED) { gammaCorrectionNonLinearMethod(I, p_mask); } - else if (method == GAMMA_LOG_BASED) { + else if (method == GAMMA_LOG_BASED) { gammaCorrectionLogMethod(I, p_mask); } - else if (method == GAMMA_CLASSIFICATION_BASED) { + else if (method == GAMMA_CLASSIFICATION_BASED) { gammaCorrectionClassBasedMethod(I, p_mask); } - else if (method == GAMMA_CDF_BASED) { + else if (method == GAMMA_CDF_BASED) { gammaCorrectionProbBasedMethod(I, p_mask); } - else if (method == GAMMA_SPATIAL_VARIANT_BASED) { + else if (method == GAMMA_SPATIAL_VARIANT_BASED) { gammaCorrectionSpatialBased(I, p_mask); } else { @@ -650,17 +648,17 @@ void gammaCorrection(const vpImage &I1, vpImage &I const vpGammaMethod &method, const vpImage *p_mask) { I2 = I1; - vp::gammaCorrection(I2, gamma, method, p_mask); + gammaCorrection(I2, gamma, method, p_mask); } void gammaCorrection(vpImage &I, const float &gamma, const vpGammaColorHandling &colorHandling, const vpGammaMethod &method, const vpImage *p_mask) { - if (method == GAMMA_SPATIAL_VARIANT_BASED) { + if (method == GAMMA_SPATIAL_VARIANT_BASED) { gammaCorrectionSpatialBased(I, p_mask); } else { - if (colorHandling == GAMMA_HSV) { + if (colorHandling == GAMMA_HSV) { const unsigned int height = I.getHeight(), width = I.getWidth(); unsigned int size = height * width; std::vector hue(size); @@ -676,7 +674,7 @@ void gammaCorrection(vpImage &I, const float &gamma, const vpGammaColorH vpImageConvert::HSVToRGBa(I_hue.bitmap, I_saturation.bitmap, I_value.bitmap, reinterpret_cast(I.bitmap), size); } - else if (colorHandling == GAMMA_RGB) { + else if (colorHandling == GAMMA_RGB) { vpImage pR, pG, pB, pa; vpImageConvert::split(I, &pR, &pG, &pB, &pa); gammaCorrection(pR, gamma, method, p_mask); @@ -699,7 +697,7 @@ void gammaCorrection(const vpImage &I1, vpImage &I2, const float const vpImage *p_mask) { I2 = I1; - vp::gammaCorrection(I2, gamma, colorHandling, method, p_mask); + gammaCorrection(I2, gamma, colorHandling, method, p_mask); } void stretchContrast(vpImage &I) @@ -728,7 +726,7 @@ void stretchContrast(const vpImage &I1, vpImage &I { // Copy I1 to I2 I2 = I1; - vp::stretchContrast(I2); + stretchContrast(I2); } void stretchContrast(vpImage &I) @@ -810,7 +808,7 @@ void stretchContrast(const vpImage &I1, vpImage &I2) { // Copy I1 to I2 I2 = I1; - vp::stretchContrast(I2); + stretchContrast(I2); } void stretchContrastHSV(vpImage &I) @@ -861,7 +859,7 @@ void stretchContrastHSV(const vpImage &I1, vpImage &I2) { // Copy I1 to I2 I2 = I1; - vp::stretchContrastHSV(I2); + stretchContrastHSV(I2); } void unsharpMask(vpImage &I, float sigma, double weight) @@ -893,7 +891,7 @@ void unsharpMask(const vpImage &I, vpImage &Ires, { // Copy I to Ires Ires = I; - vp::unsharpMask(Ires, sigma, weight); + unsharpMask(Ires, sigma, weight); } void unsharpMask(vpImage &I, float sigma, double weight) @@ -940,7 +938,7 @@ void unsharpMask(const vpImage &I, vpImage &Ires, float sigma, d { // Copy I to Ires Ires = I; - vp::unsharpMask(Ires, sigma, weight); + unsharpMask(Ires, sigma, weight); } -}; +} // namespace diff --git a/modules/imgproc/src/vpMorph.cpp b/modules/imgproc/src/vpMorph.cpp index f00b686d31..d252708a96 100644 --- a/modules/imgproc/src/vpMorph.cpp +++ b/modules/imgproc/src/vpMorph.cpp @@ -39,7 +39,11 @@ #include #include +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) namespace vp +#else +namespace visp +#endif { void fillHoles(vpImage &I @@ -102,7 +106,7 @@ void fillHoles(vpImage &I } // Perform flood fill - vp::floodFill(flood_fill_mask, vpImagePoint(0, 0), 0, 255); + floodFill(flood_fill_mask, vpImagePoint(0, 0), 0, 255); // Get current mask vpImage mask(I.getHeight(), I.getWidth()); @@ -159,4 +163,5 @@ void reconstruct(const vpImage &marker, const vpImage - *Developed at Birmingham University, School of Dentistry. Supervised by - *Gabriel Landini - *@version 1.0 + * @author Jimenez-Hernandez Francisco + * Developed at Birmingham University, School of Dentistry. Supervised by + * Gabriel Landini + * @version 1.0 * * 8 July 2010 * @@ -88,6 +88,13 @@ #include #include +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +namespace vp +#else +namespace visp +#endif +{ + #define MAX_RETINEX_SCALES 8 std::vector retinexScalesDistribution(int scaleDiv, int level, int scale) @@ -106,20 +113,20 @@ std::vector retinexScalesDistribution(int scaleDiv, int level, int scale int i; switch (level) { - case vp::RETINEX_UNIFORM: + case RETINEX_UNIFORM: for (i = 0; i < scaleDiv; ++i) { scales[static_cast(i)] = 2.0 + (i * size_step); } break; - case vp::RETINEX_LOW: + case RETINEX_LOW: size_step = std::log(scale - 2.0) / static_cast(scaleDiv); for (i = 0; i < scaleDiv; ++i) { scales[static_cast(i)] = 2.0 + std::pow(10.0, (i * size_step) / std::log(10.0)); } break; - case vp::RETINEX_HIGH: + case RETINEX_HIGH: size_step = std::log(scale - 2.0) / static_cast(scaleDiv); for (i = 0; i < scaleDiv; ++i) { scales[static_cast(i)] = scale - std::pow(10.0, (i * size_step) / std::log(10.0)); @@ -239,8 +246,6 @@ void MSRCR(vpImage &I, int v_scale, int scaleDiv, int level, double dyna } } -namespace vp -{ void retinex(vpImage &I, int scale, int scaleDiv, int level, const double dynamic, int kernelSize) { // Assert scale @@ -266,6 +271,7 @@ void retinex(const vpImage &I1, vpImage &I2, int scale, int scal int kernelSize) { I2 = I1; - vp::retinex(I2, scale, scaleDiv, level, dynamic, kernelSize); + retinex(I2, scale, scaleDiv, level, dynamic, kernelSize); } -}; + +} // namespace diff --git a/modules/imgproc/src/vpThreshold.cpp b/modules/imgproc/src/vpThreshold.cpp index 6633127d3d..97351741b8 100644 --- a/modules/imgproc/src/vpThreshold.cpp +++ b/modules/imgproc/src/vpThreshold.cpp @@ -40,8 +40,13 @@ #include #include -namespace +#if defined(VISP_BUILD_DEPRECATED_FUNCTIONS) +namespace vp +#else +namespace visp +#endif { + bool isBimodal(const std::vector &hist_float) { int modes = 0; @@ -368,10 +373,7 @@ int computeThresholdTriangle(vpHistogram &hist) return threshold; } -} // namespace -namespace vp -{ unsigned char autoThreshold(vpImage &I, const vpAutoThresholdMethod &method, const unsigned char backgroundValue, const unsigned char foregroundValue) { @@ -420,4 +422,5 @@ unsigned char autoThreshold(vpImage &I, const vpAutoThresholdMeth return threshold; } -}; + +} // namespace diff --git a/modules/io/include/visp3/io/vpDiskGrabber.h b/modules/io/include/visp3/io/vpDiskGrabber.h index 221dc48806..df2d16677f 100644 --- a/modules/io/include/visp3/io/vpDiskGrabber.h +++ b/modules/io/include/visp3/io/vpDiskGrabber.h @@ -45,6 +45,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpDiskGrabber * @@ -269,4 +274,8 @@ class VISP_EXPORT vpDiskGrabber : public vpFrameGrabber void setStep(long step) { m_image_step = step; } }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/io/include/visp3/io/vpImageIo.h b/modules/io/include/visp3/io/vpImageIo.h index b2c400aa7f..4e7c72f9b0 100644 --- a/modules/io/include/visp3/io/vpImageIo.h +++ b/modules/io/include/visp3/io/vpImageIo.h @@ -46,6 +46,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! \class vpImageIo @@ -185,4 +190,9 @@ class VISP_EXPORT vpImageIo static void writePNGtoMem(const vpImage &I, std::vector &buffer, int backend = IO_DEFAULT_BACKEND, bool saveAlpha = false); }; + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/io/include/visp3/io/vpJsonArgumentParser.h b/modules/io/include/visp3/io/vpJsonArgumentParser.h index 4cee71ee34..f15f8e9f07 100644 --- a/modules/io/include/visp3/io/vpJsonArgumentParser.h +++ b/modules/io/include/visp3/io/vpJsonArgumentParser.h @@ -33,6 +33,7 @@ #ifndef _vpJsonArgumentParser_h_ #define _vpJsonArgumentParser_h_ + #include #if defined(VISP_HAVE_NLOHMANN_JSON) @@ -66,6 +67,12 @@ nlohmann::json convertCommandLineArgument(const std::string &arg) nlohmann::json j = arg; return j; } + +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! \class vpJsonArgumentParser \ingroup module_io_cmd_parser @@ -78,53 +85,53 @@ nlohmann::json convertCommandLineArgument(const std::string &arg) A very basic program that uses both a JSON file and command line arguments can be found below: \code{.cpp} - #include - #include - int main(int argc, char* argv[]) - { - double d = 1.0; - std::string s = "Default"; - - vpJsonArgumentParser parser("Example program for arguments with vpJsonArgumentParser", "config", "/"); - - parser.add_argument("scalar", d, true, "An important value: must be defined by the user") - .add_argument("string", s, false, "An optional value: if left unspecified, will default to its initialized value (\"Default\")") - .parse(argc, argv); - - std::cout << "Scalar = " << d << std::endl; - std::cout << "String = " << s << std::endl; - } + #include + #include + int main(int argc, char* argv[]) + { + double d = 1.0; + std::string s = "Default"; + + vpJsonArgumentParser parser("Example program for arguments with vpJsonArgumentParser", "config", "/"); + + parser.add_argument("scalar", d, true, "An important value: must be defined by the user") + .add_argument("string", s, false, "An optional value: if left unspecified, will default to its initialized value (\"Default\")") + .parse(argc, argv); + + std::cout << "Scalar = " << d << std::endl; + std::cout << "String = " << s << std::endl; + } \endcode Compiling this sample and calling the program with the arguments from the command line would yield: \code{.sh} - $ ./program scalar 2.0 string "A new value" - Scalar = 2.0 - String = a new value - $ ./program scalar 2.0 - Scalar = 2.0 - String = default + $ ./program scalar 2.0 string "A new value" + Scalar = 2.0 + String = a new value + $ ./program scalar 2.0 + Scalar = 2.0 + String = default \endcode Here the arguments are specified from the command line. Since the "string" argument is optional, it does not have to be specified. For programs with more arguments it is helpful to use a JSON file that contains a base configuration. For the program above, a JSON file could look like: \code{.json} - { - "scalar": 3.0, - "string": "Some base value" - } + { + "scalar": 3.0, + "string": "Some base value" + } \endcode we could then call the program with: \code{.sh} - $ ./program config my_settings.json - Scalar = 3.0 - String = Some base value + $ ./program config my_settings.json + Scalar = 3.0 + String = Some base value \endcode The values contained in the JSON file can be overridden with command line arguments \code{.sh} - $ ./program config my_settings.json scalar 5 - Scalar = 5.0 - String = Some base value + $ ./program config my_settings.json scalar 5 + Scalar = 5.0 + String = Some base value \endcode The program can also be called with the "-h" or "--help" argument to display the help associated to the arguments, as well as an example json configuration file @@ -177,7 +184,7 @@ class VISP_EXPORT vpJsonArgumentParser template vpJsonArgumentParser &addArgument(const std::string &name, T ¶meter, const bool required = true, const std::string &help = "No description") { - const auto getter = [name, this](nlohmann::json &j, bool create) -> nlohmann::json *{ + const auto getter = [name, this](nlohmann::json &j, bool create) -> nlohmann::json * { size_t pos = 0; nlohmann::json *f = &j; std::string token; @@ -261,6 +268,10 @@ class VISP_EXPORT vpJsonArgumentParser nlohmann::json exampleJson; // Example JSON argument file: displayed when user calls for help }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif // VISP_HAVE_NLOHMANN_JSON #endif diff --git a/modules/io/include/visp3/io/vpParseArgv.h b/modules/io/include/visp3/io/vpParseArgv.h index aa83214d54..20fb09ded3 100644 --- a/modules/io/include/visp3/io/vpParseArgv.h +++ b/modules/io/include/visp3/io/vpParseArgv.h @@ -29,6 +29,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! \class vpParseArgv \ingroup module_io_cmd_parser @@ -39,102 +44,102 @@ name with more than one character. \code -#include -#include -#include + #include + #include + #include -// Usage : [-bool] [-int ] [-long ] -// [-float ] [-double ] [-string ] [-h] -int main(int argc, const char ** argv) -{ - // Variables to set by command line parsing - bool b_val = false; - int i_val = 10; - long l_val = 123456; - float f_val = 0.1f; - double d_val = M_PI; - char *s_val; - - // Parse the command line to set the variables - vpParseArgv::vpArgvInfo argTable[] = + // Usage : [-bool] [-int ] [-long ] + // [-float ] [-double ] [-string ] [-h] + int main(int argc, const char ** argv) { - {"-bool", vpParseArgv::ARGV_CONSTANT_BOOL, 0, (char *) &b_val, - "Flag enabled."}, - {"-int", vpParseArgv::ARGV_INT, (char*) nullptr, (char *) &i_val, - "An integer value."}, - {"-long", vpParseArgv::ARGV_LONG, (char*) nullptr, (char *) &l_val, - "An integer value."}, - {"-float", vpParseArgv::ARGV_FLOAT, (char*) nullptr, (char *) &f_val, - "A float value."}, - {"-double", vpParseArgv::ARGV_DOUBLE, (char*) nullptr, (char *) &d_val, - "A double value."}, - {"-string", vpParseArgv::ARGV_STRING, (char*) nullptr, (char *) &s_val, - "A string value."}, - {"-h", vpParseArgv::ARGV_HELP, (char*) nullptr, (char *) nullptr, - "Print the help."}, - {(char*) nullptr, vpParseArgv::ARGV_END, (char*) nullptr, (char*) nullptr, (char*) nullptr} } ; - - // Read the command line options - if(vpParseArgv::parse(&argc, argv, argTable, - vpParseArgv::ARGV_NO_LEFTOVERS | - vpParseArgv::ARGV_NO_ABBREV | - vpParseArgv::ARGV_NO_DEFAULTS)) { - return (false); - } + // Variables to set by command line parsing + bool b_val = false; + int i_val = 10; + long l_val = 123456; + float f_val = 0.1f; + double d_val = M_PI; + char *s_val; + + // Parse the command line to set the variables + vpParseArgv::vpArgvInfo argTable[] = + { + {"-bool", vpParseArgv::ARGV_CONSTANT_BOOL, 0, (char *) &b_val, + "Flag enabled."}, + {"-int", vpParseArgv::ARGV_INT, (char*) nullptr, (char *) &i_val, + "An integer value."}, + {"-long", vpParseArgv::ARGV_LONG, (char*) nullptr, (char *) &l_val, + "An integer value."}, + {"-float", vpParseArgv::ARGV_FLOAT, (char*) nullptr, (char *) &f_val, + "A float value."}, + {"-double", vpParseArgv::ARGV_DOUBLE, (char*) nullptr, (char *) &d_val, + "A double value."}, + {"-string", vpParseArgv::ARGV_STRING, (char*) nullptr, (char *) &s_val, + "A string value."}, + {"-h", vpParseArgv::ARGV_HELP, (char*) nullptr, (char *) nullptr, + "Print the help."}, + {(char*) nullptr, vpParseArgv::ARGV_END, (char*) nullptr, (char*) nullptr, (char*) nullptr} } ; + + // Read the command line options + if(vpParseArgv::parse(&argc, argv, argTable, + vpParseArgv::ARGV_NO_LEFTOVERS | + vpParseArgv::ARGV_NO_ABBREV | + vpParseArgv::ARGV_NO_DEFAULTS)) { + return (false); + } - // b_val, i_val, l_val, f_val, d_val, s_val may have new values -} + // b_val, i_val, l_val, f_val, d_val, s_val may have new values + } \endcode The code below shows an other way to parse command line arguments using vpParseArgv class. Here command line options are only one character long. \code -#include -#include -#include -#include + #include + #include + #include + #include -// List of allowed command line options -#define GETOPTARGS "bi:l:f:d:h" // double point mean here that the preceding option request an argument + // List of allowed command line options + #define GETOPTARGS "bi:l:f:d:h" // double point mean here that the preceding option request an argument -// Usage : [-b] [-i ] [-l ] -// [-f ] [-d ] [-s ] [-h] -int main(int argc, const char ** argv) -{ - // Variables to set by command line parsing - bool b_val = false; - int i_val = 10; - long l_val = 123456; - float f_val = 0.1f; - double d_val = M_PI; - std::string s_val; - - // Parse the command line to set the variables - const char *optarg; - int c; - while ((c = vpParseArgv::parse(argc, argv, GETOPTARGS, &optarg)) > 1) { - - switch (c) { - case 'b': b_val = true; break; - case 'i': i_val = atoi(optarg); break; - case 'l': l_val = atol(optarg); break; - case 'f': f_val = static_cast(atof(optarg)); break; - case 'd': d_val = atof(optarg); break; - case 's': s_val = std::string(optarg); break; - case 'h': printf("Usage: ...\n"); return EXIT_SUCCESS; break; - - default: - printf("Usage: ...\n"); return EXIT_SUCCESS; break; + // Usage : [-b] [-i ] [-l ] + // [-f ] [-d ] [-s ] [-h] + int main(int argc, const char ** argv) + { + // Variables to set by command line parsing + bool b_val = false; + int i_val = 10; + long l_val = 123456; + float f_val = 0.1f; + double d_val = M_PI; + std::string s_val; + + // Parse the command line to set the variables + const char *optarg; + int c; + while ((c = vpParseArgv::parse(argc, argv, GETOPTARGS, &optarg)) > 1) { + + switch (c) { + case 'b': b_val = true; break; + case 'i': i_val = atoi(optarg); break; + case 'l': l_val = atol(optarg); break; + case 'f': f_val = static_cast(atof(optarg)); break; + case 'd': d_val = atof(optarg); break; + case 's': s_val = std::string(optarg); break; + case 'h': printf("Usage: ...\n"); return EXIT_SUCCESS; break; + + default: + printf("Usage: ...\n"); return EXIT_SUCCESS; break; + } + } + if ((c == 1) || (c == -1)) { + // standalone param or error + printf("Usage: ...\n"); + return EXIT_FAILURE; } - } - if ((c == 1) || (c == -1)) { - // standalone param or error - printf("Usage: ...\n"); - return EXIT_FAILURE; - } - // b_val, i_val, l_val, f_val, d_val, s_val may have new values -} + // b_val, i_val, l_val, f_val, d_val, s_val may have new values + } \endcode */ @@ -145,7 +150,8 @@ class VISP_EXPORT vpParseArgv /*! Legal values for the type field of a vpArgvInfo. */ - typedef enum { + typedef enum + { ARGV_CONSTANT, ///< Stand alone argument. Same as vpParseArgv::ARGV_CONSTANT_INT. ARGV_CONSTANT_INT, ///< Stand alone argument associated to an int var that is set to 1. ARGV_CONSTANT_BOOL, ///< Stand alone argument associated to a bool var that is set to true. @@ -164,7 +170,8 @@ class VISP_EXPORT vpParseArgv /*! Flag bits. */ - typedef enum { + typedef enum + { ARGV_NO_DEFAULTS = 0x1, ///< No default options like -help. ARGV_NO_LEFTOVERS = 0x2, ///< Print an error message if an option is not in the argument list. ARGV_NO_ABBREV = 0x4, ///< No abrevation. Print an error message if an option is abrevated (ie "-i" in place of @@ -178,7 +185,8 @@ class VISP_EXPORT vpParseArgv Structure used to specify how to handle argv options. */ - typedef struct { + typedef struct + { const char *key; ///< The key string that flags the option in the argv array. vpArgvType type; ///< Indicates option type. const char *src; ///< Value to be used in setting dst; usage depends on type. @@ -196,4 +204,8 @@ class VISP_EXPORT vpParseArgv static void printUsage(vpArgvInfo *argTable, int flags); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/io/include/visp3/io/vpVideoReader.h b/modules/io/include/visp3/io/vpVideoReader.h index a6ea82161e..6a832019d8 100644 --- a/modules/io/include/visp3/io/vpVideoReader.h +++ b/modules/io/include/visp3/io/vpVideoReader.h @@ -43,6 +43,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_VIDEOIO) && defined(HAVE_OPENCV_HIGHGUI) #include #include @@ -375,4 +380,8 @@ class VISP_EXPORT vpVideoReader : public vpFrameGrabber void getProperties(); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/io/include/visp3/io/vpVideoWriter.h b/modules/io/include/visp3/io/vpVideoWriter.h index 85d6cdd977..594400d516 100644 --- a/modules/io/include/visp3/io/vpVideoWriter.h +++ b/modules/io/include/visp3/io/vpVideoWriter.h @@ -43,6 +43,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_VIDEOIO) && defined(HAVE_OPENCV_HIGHGUI) #include #include @@ -258,4 +263,8 @@ class VISP_EXPORT vpVideoWriter static std::string getExtension(const std::string &filename); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/io/src/image/private/vpImageIoBackend.h b/modules/io/src/image/private/vpImageIoBackend.h index 56fcc2e3ba..bd40585b8c 100644 --- a/modules/io/src/image/private/vpImageIoBackend.h +++ b/modules/io/src/image/private/vpImageIoBackend.h @@ -41,6 +41,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + // Portable FloatMap format (PFM) // Portable Graymap format (PGM) // Portable Pixmap format (PPM) @@ -133,4 +138,8 @@ void writePNGtoMemStb(const vpImage &I, std::vector &I, std::vector &buffer, bool saveAlpha); #endif +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/io/src/image/private/vpImageIoLibjpeg.cpp b/modules/io/src/image/private/vpImageIoLibjpeg.cpp index 692183d742..029cc06804 100644 --- a/modules/io/src/image/private/vpImageIoLibjpeg.cpp +++ b/modules/io/src/image/private/vpImageIoLibjpeg.cpp @@ -50,6 +50,10 @@ #if defined(VISP_HAVE_JPEG) +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Write the content of the image bitmap in the file which name is given by \e filename. This function writes a JPEG file. @@ -332,4 +336,9 @@ void readJPEGLibjpeg(vpImage &I, const std::string &filename) jpeg_destroy_decompress(&cinfo); fclose(file); } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/io/src/image/private/vpImageIoLibpng.cpp b/modules/io/src/image/private/vpImageIoLibpng.cpp index e7b3afcc5b..03f54ae5d5 100644 --- a/modules/io/src/image/private/vpImageIoLibpng.cpp +++ b/modules/io/src/image/private/vpImageIoLibpng.cpp @@ -49,6 +49,10 @@ #if defined(VISP_HAVE_PNG) +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Write the content of the image bitmap in the file which name is given by \e filename. This function writes a PNG file. @@ -598,4 +602,9 @@ void readPNGLibpng(vpImage &I, const std::string &filename) png_destroy_read_struct(&png_ptr, &info_ptr, nullptr); fclose(file); } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/io/src/image/private/vpImageIoOpenCV.cpp b/modules/io/src/image/private/vpImageIoOpenCV.cpp index dceed26214..45e92ea69f 100644 --- a/modules/io/src/image/private/vpImageIoOpenCV.cpp +++ b/modules/io/src/image/private/vpImageIoOpenCV.cpp @@ -59,6 +59,10 @@ #if ((VISP_HAVE_OPENCV_VERSION >= 0x030000) && defined(HAVE_OPENCV_IMGCODECS)) || ((VISP_HAVE_OPENCV_VERSION < 0x030000) \ && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_IMGPROC)) +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! Read the contents of the image file, allocate memory for the corresponding gray level image, if necessary convert the data in @@ -302,4 +306,8 @@ void writePNGtoMemOpenCV(const vpImage &I_color, std::vector #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #ifndef DOXYGEN_SHOULD_SKIP_THIS /*! * Decode the PNM image header. @@ -837,3 +842,7 @@ void vp_writePPM(const vpImage &I, const std::string &filename) fflush(f); fclose(f); } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/io/src/image/private/vpImageIoSimd.cpp b/modules/io/src/image/private/vpImageIoSimd.cpp index 261af7012f..a6d22e74ae 100644 --- a/modules/io/src/image/private/vpImageIoSimd.cpp +++ b/modules/io/src/image/private/vpImageIoSimd.cpp @@ -42,6 +42,11 @@ #include "vpImageIoBackend.h" #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + void readSimdlib(vpImage &I, const std::string &filename) { size_t stride = 0, width = 0, height = 0; @@ -91,4 +96,9 @@ void writePNGSimdlib(const vpImage &I, const std::string &filename) SimdImageSaveToFile((const uint8_t *)I.bitmap, I.getWidth() * 4, I.getWidth(), I.getHeight(), SimdPixelFormatRgba32, SimdImageFilePng, 90, filename.c_str()); } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/io/src/image/private/vpImageIoStb.cpp b/modules/io/src/image/private/vpImageIoStb.cpp index 5db5a9f3bd..5d91698446 100644 --- a/modules/io/src/image/private/vpImageIoStb.cpp +++ b/modules/io/src/image/private/vpImageIoStb.cpp @@ -57,6 +57,11 @@ #define STB_IMAGE_WRITE_IMPLEMENTATION #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + void readStb(vpImage &I, const std::string &filename) { int width = 0, height = 0, channels = 0; @@ -266,4 +271,9 @@ void writePNGtoMemStb(const vpImage &I_color, std::vector #endif } } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/io/src/image/private/vpImageIoTinyEXR.cpp b/modules/io/src/image/private/vpImageIoTinyEXR.cpp index d26e5078aa..f03d204cdb 100644 --- a/modules/io/src/image/private/vpImageIoTinyEXR.cpp +++ b/modules/io/src/image/private/vpImageIoTinyEXR.cpp @@ -51,6 +51,11 @@ #define TINYEXR_IMPLEMENTATION #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + void readEXRTiny(vpImage &I, const std::string &filename) { EXRVersion exr_version; @@ -319,4 +324,8 @@ void writeEXRTiny(const vpImage &I, const std::string &filename) free(header.pixel_types); } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/io/src/image/vpImageIo.cpp b/modules/io/src/image/vpImageIo.cpp index 567969e0d3..7d26b2b1af 100644 --- a/modules/io/src/image/vpImageIo.cpp +++ b/modules/io/src/image/vpImageIo.cpp @@ -41,6 +41,10 @@ #include "private/vpImageIoBackend.h" +#if defined(ENABLE_VISP_NAMESPACE) +using namespace visp; +#endif + vpImageIo::vpImageFormatType vpImageIo::getFormat(const std::string &filename) { std::string ext = vpImageIo::getExtension(filename); diff --git a/modules/io/src/tools/vpJsonArgumentParser.cpp b/modules/io/src/tools/vpJsonArgumentParser.cpp index 9c605fd767..bcf1029e82 100644 --- a/modules/io/src/tools/vpJsonArgumentParser.cpp +++ b/modules/io/src/tools/vpJsonArgumentParser.cpp @@ -27,13 +27,17 @@ * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE. */ + +#include #include #include -#include #include - #if defined(VISP_HAVE_NLOHMANN_JSON) +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif using json = nlohmann::json; //! json namespace shortcut @@ -150,4 +154,8 @@ void vpJsonArgumentParser::parse(int argc, const char *argv[]) } } +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/io/src/tools/vpParseArgv.cpp b/modules/io/src/tools/vpParseArgv.cpp index 5dcc3755c1..e0b454ce86 100644 --- a/modules/io/src/tools/vpParseArgv.cpp +++ b/modules/io/src/tools/vpParseArgv.cpp @@ -32,6 +32,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /* * Default table of argument descriptors. These are normally available * in every application. @@ -39,7 +44,7 @@ vpParseArgv::vpArgvInfo vpParseArgv::defaultTable[2] = { {"-help", ARGV_HELP, (char *)nullptr, (char *)nullptr, "Print summary of command-line options and abort.\n"}, - {nullptr, ARGV_END, (char *)nullptr, (char *)nullptr, (char *)nullptr}}; + {nullptr, ARGV_END, (char *)nullptr, (char *)nullptr, (char *)nullptr} }; int (*handlerProc1)(const char *dst, const char *key, const char *argument); int (*handlerProc2)(const char *dst, const char *key, int valargc, const char **argument); @@ -94,7 +99,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i if (flags & ARGV_DONT_SKIP_FIRST_ARG) { srcIndex = dstIndex = 0; argc = *argcPtr; - } else { + } + else { srcIndex = dstIndex = 1; argc = *argcPtr - 1; } @@ -116,7 +122,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i for (unsigned int i = 0; i < 2; ++i) { if (i == 0) { infoPtr = argTable; - } else { + } + else { infoPtr = defaultTable; } for (; infoPtr->type != ARGV_END; ++infoPtr) { @@ -175,7 +182,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i for (unsigned long i = 0; i < nargs; ++i) { if (argc == 0) { goto missingArg; - } else { + } + else { char *endPtr = nullptr; *(((int *)infoPtr->dst) + i) = (int)strtol(argv[srcIndex], &endPtr, 0); @@ -195,7 +203,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i for (unsigned long i = 0; i < nargs; ++i) { if (argc == 0) { goto missingArg; - } else { + } + else { char *endPtr = nullptr; *(((long *)infoPtr->dst) + i) = strtol(argv[srcIndex], &endPtr, 0); @@ -215,7 +224,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i for (unsigned long i = 0; i < nargs; ++i) { if (argc == 0) { goto missingArg; - } else { + } + else { *(((const char **)infoPtr->dst) + i) = argv[srcIndex]; srcIndex++; argc--; @@ -232,7 +242,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i for (unsigned long i = 0; i < nargs; ++i) { if (argc == 0) { goto missingArg; - } else { + } + else { char *endPtr; *(((float *)infoPtr->dst) + i) = (float)strtod(argv[srcIndex], &endPtr); // Here we use strtod @@ -253,7 +264,8 @@ bool vpParseArgv::parse(int *argcPtr, const char **argv, vpArgvInfo *argTable, i for (unsigned long i = 0; i < nargs; ++i) { if (argc == 0) { goto missingArg; - } else { + } + else { char *endPtr; *(((double *)infoPtr->dst) + i) = strtod(argv[srcIndex], &endPtr); @@ -379,7 +391,8 @@ void vpParseArgv::printUsage(vpArgvInfo *argTable, int flags) while (numSpaces > 0) { if (numSpaces >= NUM_SPACES) { FPRINTF(stderr, "%s", spaces); - } else { + } + else { FPRINTF(stderr, "%s", spaces + NUM_SPACES - numSpaces); } numSpaces -= NUM_SPACES; @@ -522,38 +535,45 @@ int vpParseArgv::parse(int argc, const char **argv, const char *validOpts, const // next argv is the param iArg++; pszParam = psz; - } else { - // reached end of args looking for param - // option specified without parameter + } + else { + // reached end of args looking for param + // option specified without parameter chOpt = -1; pszParam = &(argv[iArg][0]); } - } else { - // param is attached to option + } + else { + // param is attached to option pszParam = psz; } - } else { - // option is alone, has no parameter } - } else { - // option specified is not in list of valid options + else { + // option is alone, has no parameter + } + } + else { + // option specified is not in list of valid options chOpt = -1; pszParam = &(argv[iArg][0]); } - } else { - // though option specifier was given, option character - // is not alpha or was was not specified + } + else { + // though option specifier was given, option character + // is not alpha or was was not specified chOpt = -1; pszParam = &(argv[iArg][0]); } - } else { - // standalone arg given with no option specifier + } + else { + // standalone arg given with no option specifier chOpt = 1; pszParam = &(argv[iArg][0]); } - } else { - // end of argument list + } + else { + // end of argument list chOpt = 0; } @@ -561,3 +581,7 @@ int vpParseArgv::parse(int argc, const char **argv, const char *validOpts, const *param = pszParam; return (chOpt); } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/io/src/video/vpDiskGrabber.cpp b/modules/io/src/video/vpDiskGrabber.cpp index f8c923d542..7f4a01bfb6 100644 --- a/modules/io/src/video/vpDiskGrabber.cpp +++ b/modules/io/src/video/vpDiskGrabber.cpp @@ -33,6 +33,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + vpDiskGrabber::vpDiskGrabber() : m_image_number(0), m_image_number_next(0), m_image_step(1), m_number_of_zero(0), m_directory("/tmp"), m_base_name("I"), m_extension("pgm"), m_use_generic_name(false), m_generic_name("empty") @@ -247,3 +252,7 @@ void vpDiskGrabber::setGenericName(const std::string &generic_name) m_generic_name = generic_name; m_use_generic_name = true; } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/io/src/video/vpVideoReader.cpp b/modules/io/src/video/vpVideoReader.cpp index 600a63695c..e157bf1aef 100644 --- a/modules/io/src/video/vpVideoReader.cpp +++ b/modules/io/src/video/vpVideoReader.cpp @@ -45,6 +45,11 @@ #include #include // numeric_limits +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! Basic constructor. */ @@ -906,3 +911,7 @@ bool vpVideoReader::isVideoFormat() const return false; } } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/io/src/video/vpVideoWriter.cpp b/modules/io/src/video/vpVideoWriter.cpp index d21829e200..e05358dc7b 100644 --- a/modules/io/src/video/vpVideoWriter.cpp +++ b/modules/io/src/video/vpVideoWriter.cpp @@ -40,6 +40,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #if defined(HAVE_OPENCV_IMGPROC) #include #endif @@ -50,10 +55,10 @@ vpVideoWriter::vpVideoWriter() : #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) - m_writer(), m_framerate(25.0), + m_writer(), m_framerate(25.0), #endif - m_formatType(FORMAT_UNKNOWN), m_videoName(), m_frameName(), m_initFileName(false), m_isOpen(false), m_frameCount(0), - m_firstFrame(0), m_width(0), m_height(0), m_frameStep(1) + m_formatType(FORMAT_UNKNOWN), m_videoName(), m_frameName(), m_initFileName(false), m_isOpen(false), m_frameCount(0), + m_firstFrame(0), m_width(0), m_height(0), m_frameStep(1) { #if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) #if (VISP_HAVE_OPENCV_VERSION >= 0x030000) @@ -67,7 +72,7 @@ vpVideoWriter::vpVideoWriter() /*! Basic destructor. */ -vpVideoWriter::~vpVideoWriter() {} +vpVideoWriter::~vpVideoWriter() { } /*! It enables to set the path and the name of the video or sequence of images @@ -121,8 +126,9 @@ void vpVideoWriter::open(vpImage &I) m_formatType == FORMAT_PNG) { m_width = I.getWidth(); m_height = I.getHeight(); - } else if (m_formatType == FORMAT_AVI || m_formatType == FORMAT_MPEG || m_formatType == FORMAT_MPEG4 || - m_formatType == FORMAT_MOV) { + } + else if (m_formatType == FORMAT_AVI || m_formatType == FORMAT_MPEG || m_formatType == FORMAT_MPEG4 || + m_formatType == FORMAT_MOV) { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) m_writer = cv::VideoWriter(m_videoName, m_fourcc, m_framerate, cv::Size(static_cast(I.getWidth()), static_cast(I.getHeight()))); @@ -160,8 +166,9 @@ void vpVideoWriter::open(vpImage &I) m_formatType == FORMAT_PNG) { m_width = I.getWidth(); m_height = I.getHeight(); - } else if (m_formatType == FORMAT_AVI || m_formatType == FORMAT_MPEG || m_formatType == FORMAT_MPEG4 || - m_formatType == FORMAT_MOV) { + } + else if (m_formatType == FORMAT_AVI || m_formatType == FORMAT_MPEG || m_formatType == FORMAT_MPEG4 || + m_formatType == FORMAT_MOV) { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) m_writer = cv::VideoWriter(m_videoName, m_fourcc, m_framerate, cv::Size(static_cast(I.getWidth()), static_cast(I.getHeight()))); @@ -200,7 +207,8 @@ void vpVideoWriter::saveFrame(vpImage &I) snprintf(name, FILENAME_MAX, m_videoName.c_str(), m_frameCount); vpImageIo::write(I, name); m_frameName = std::string(name); - } else { + } + else { #if defined(VISP_HAVE_OPENCV) && defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) cv::Mat matFrame; vpImageConvert::convert(I, matFrame); @@ -232,7 +240,8 @@ void vpVideoWriter::saveFrame(vpImage &I) snprintf(name, FILENAME_MAX, m_videoName.c_str(), m_frameCount); vpImageIo::write(I, name); m_frameName = std::string(name); - } else { + } + else { #if defined(HAVE_OPENCV_HIGHGUI) && defined(HAVE_OPENCV_VIDEOIO) #if (VISP_HAVE_OPENCV_VERSION >= 0x030000) cv::Mat matFrame, rgbMatFrame; @@ -339,3 +348,7 @@ void vpVideoWriter::setFirstFrameIndex(int first_frame) } m_firstFrame = first_frame; } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/tracker/blob/include/visp3/blob/vpDot.h b/modules/tracker/blob/include/visp3/blob/vpDot.h index fb76621f56..bca93ec2f3 100644 --- a/modules/tracker/blob/include/visp3/blob/vpDot.h +++ b/modules/tracker/blob/include/visp3/blob/vpDot.h @@ -58,6 +58,11 @@ #pragma comment(linker, "/STACK:256000000") // Increase max recursion depth #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpDot * @@ -414,4 +419,7 @@ class VISP_EXPORT vpDot : public vpTracker vpColor color = vpColor::red, unsigned int thickness = 1); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/tracker/blob/include/visp3/blob/vpDot2.h b/modules/tracker/blob/include/visp3/blob/vpDot2.h index 128108d445..914164da39 100644 --- a/modules/tracker/blob/include/visp3/blob/vpDot2.h +++ b/modules/tracker/blob/include/visp3/blob/vpDot2.h @@ -51,6 +51,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpDot2 * @@ -162,10 +167,10 @@ class VISP_EXPORT vpDot2 : public vpTracker { vpRect bbox; - bbox.setRect(this->bbox_u_min, this->bbox_v_min, this->bbox_u_max - this->bbox_u_min + 1, - this->bbox_v_max - this->bbox_v_min + 1); + bbox.setRect(this->bbox_u_min, this->bbox_v_min, (this->bbox_u_max - this->bbox_u_min) + 1, + (this->bbox_v_max - this->bbox_v_min) + 1); - return (bbox); + return bbox; }; /*! @@ -192,7 +197,7 @@ class VISP_EXPORT vpDot2 : public vpTracker * \return The list of all the images points on the dot * border. This list is update after a call to track(). */ - std::list getEdges() const { return (this->ip_edges_list); }; + std::list getEdges() const { return this->ip_edges_list; }; /*! * Get the percentage of sampled points that are considered non conform @@ -284,12 +289,15 @@ class VISP_EXPORT vpDot2 : public vpTracker */ void setEllipsoidBadPointsPercentage(const double &percentage = 0.0) { - if (percentage < 0.) + if (percentage < 0.) { allowedBadPointsPercentage_ = 0.; - else if (percentage > 1.) + } + else if (percentage > 1.) { allowedBadPointsPercentage_ = 1.; - else + } + else { allowedBadPointsPercentage_ = percentage; + } } void setEllipsoidShapePrecision(const double &ellipsoidShapePrecision); @@ -329,10 +337,12 @@ class VISP_EXPORT vpDot2 : public vpTracker */ inline void setGrayLevelMin(const unsigned int &min) { - if (min > 255) + if (min > 255) { this->gray_level_min = 255; - else + } + else { this->gray_level_min = min; + } }; /*! @@ -365,6 +375,13 @@ class VISP_EXPORT vpDot2 : public vpTracker static void trackAndDisplay(vpDot2 dot[], const unsigned int &n, vpImage &I, std::vector &cogs, vpImagePoint *cogStar = nullptr); + // Static funtions + static void display(const vpImage &I, const vpImagePoint &cog, + const std::list &edges_list, vpColor color = vpColor::red, + unsigned int thickness = 1); + static void display(const vpImage &I, const vpImagePoint &cog, const std::list &edges_list, + vpColor color = vpColor::red, unsigned int thickness = 1); + #ifdef VISP_BUILD_DEPRECATED_FUNCTIONS public: #else @@ -520,13 +537,9 @@ class VISP_EXPORT vpDot2 : public vpTracker unsigned int firstBorder_u; unsigned int firstBorder_v; - // Static funtions -public: - static void display(const vpImage &I, const vpImagePoint &cog, - const std::list &edges_list, vpColor color = vpColor::red, - unsigned int thickness = 1); - static void display(const vpImage &I, const vpImagePoint &cog, const std::list &edges_list, - vpColor color = vpColor::red, unsigned int thickness = 1); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif #endif diff --git a/modules/tracker/blob/src/dots/vpDot.cpp b/modules/tracker/blob/src/dots/vpDot.cpp index c87d4949d7..20124f9eb8 100644 --- a/modules/tracker/blob/src/dots/vpDot.cpp +++ b/modules/tracker/blob/src/dots/vpDot.cpp @@ -48,6 +48,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /* \class vpDot \brief Track a white dot @@ -947,3 +952,7 @@ void vpDot::display(const vpImage &I, const vpImagePoint &cog, const std documentation) to the stream \e os, and returns a reference to the stream. */ 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 d4118dcc55..3275d469ba 100644 --- a/modules/tracker/blob/src/dots/vpDot2.cpp +++ b/modules/tracker/blob/src/dots/vpDot2.cpp @@ -54,6 +54,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /****************************************************************************** * * CONSTRUCTORS AND DESTRUCTORS @@ -2506,3 +2511,7 @@ void vpDot2::display(const vpImage &I, const vpImagePoint &cog, const st documentation) to the stream \e os, and returns a reference to the stream. */ VISP_EXPORT std::ostream &operator<<(std::ostream &os, vpDot2 &d) { return (os << "(" << d.getCog() << ")"); } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/tracker/me/include/visp3/me/vpMe.h b/modules/tracker/me/include/visp3/me/vpMe.h index 777a113aaa..070fba3fe5 100644 --- a/modules/tracker/me/include/visp3/me/vpMe.h +++ b/modules/tracker/me/include/visp3/me/vpMe.h @@ -43,6 +43,10 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif /*! * \class vpMe * \ingroup module_me @@ -135,31 +139,6 @@ class VISP_EXPORT vpMe NORMALIZED_THRESHOLD = 1 } vpLikelihoodThresholdType; -private: - vpLikelihoodThresholdType m_likelihood_threshold_type; //!< Likelihood threshold type - //! Old likelihood ratio threshold (to be avoided) or easy-to-use normalized threshold: minimal contrast - double m_threshold; - double m_thresholdMarginRatio; //!< The ratio of the initial contrast to use to initialize the contrast threshold of the vpMeSite. - double m_minThreshold; //!< The minimum moving-edge threshold in grey level used when the contrast threshold of the vpMeSites is automatically computed. - bool m_useAutomaticThreshold; //!< Set to true if the user wants to automatically compute the vpMeSite contrast thresholds, false if the user wants to use a global threshold. - double m_mu1; //!< Contrast continuity parameter (left boundary) - double m_mu2; //!< Contrast continuity parameter (right boundary) - double m_min_samplestep; - unsigned int m_anglestep; - int m_mask_sign; - unsigned int m_range; //! Seek range - on both sides of the reference pixel - double m_sample_step; //! Distance between sampled points in pixels - int m_ntotal_sample; - int m_points_to_track; //!< Expected number of points to track - //! Convolution masks' size in pixels (masks are square) - unsigned int m_mask_size; - //! The number of convolution masks available for tracking ; defines resolution - unsigned int m_mask_number; - //! Strip: defines a "security strip" such that when seeking extremities - //! cannot return a new extremity which is too close to the frame borders - int m_strip; - vpMatrix *m_mask; //!< Array of matrices defining the different masks (one for every angle step). - public: /*! * Default constructor. @@ -195,8 +174,9 @@ class VISP_EXPORT vpMe */ void checkSamplestep(double &sample_step) { - if (sample_step < m_min_samplestep) + if (sample_step < m_min_samplestep) { sample_step = m_min_samplestep; + } } /*! @@ -518,6 +498,31 @@ class VISP_EXPORT vpMe */ void setLikelihoodThresholdType(const vpLikelihoodThresholdType likelihood_threshold_type) { m_likelihood_threshold_type = likelihood_threshold_type; } +private: + vpLikelihoodThresholdType m_likelihood_threshold_type; //!< Likelihood threshold type + //! Old likelihood ratio threshold (to be avoided) or easy-to-use normalized threshold: minimal contrast + double m_threshold; + double m_thresholdMarginRatio; //!< The ratio of the initial contrast to use to initialize the contrast threshold of the vpMeSite. + double m_minThreshold; //!< The minimum moving-edge threshold in grey level used when the contrast threshold of the vpMeSites is automatically computed. + bool m_useAutomaticThreshold; //!< Set to true if the user wants to automatically compute the vpMeSite contrast thresholds, false if the user wants to use a global threshold. + double m_mu1; //!< Contrast continuity parameter (left boundary) + double m_mu2; //!< Contrast continuity parameter (right boundary) + double m_min_samplestep; + unsigned int m_anglestep; + int m_mask_sign; + unsigned int m_range; //! Seek range - on both sides of the reference pixel + double m_sample_step; //! Distance between sampled points in pixels + int m_ntotal_sample; + int m_points_to_track; //!< Expected number of points to track + //! Convolution masks' size in pixels (masks are square) + unsigned int m_mask_size; + //! The number of convolution masks available for tracking ; defines resolution + unsigned int m_mask_number; + //! Strip: defines a "security strip" such that when seeking extremities + //! cannot return a new extremity which is too close to the frame borders + int m_strip; + vpMatrix *m_mask; //!< Array of matrices defining the different masks (one for every angle step). + #ifdef VISP_HAVE_NLOHMANN_JSON /*! * @brief Convert a vpMe object to a JSON representation. @@ -619,7 +624,7 @@ inline void from_json(const nlohmann::json &j, vpMe &me) assert((mus.size() == 2)); me.setMu1(mus[0]); me.setMu2(mus[1]); - } +} me.setMinSampleStep(j.value("minSampleStep", me.getMinSampleStep())); me.setSampleStep(j.value("sampleStep", me.getSampleStep())); me.setRange(j.value("range", me.getRange())); @@ -643,4 +648,9 @@ inline void from_json(const nlohmann::json &j, vpMe &me) #endif + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/tracker/me/include/visp3/me/vpMeEllipse.h b/modules/tracker/me/include/visp3/me/vpMeEllipse.h index c0cdab267f..0eadccaf06 100644 --- a/modules/tracker/me/include/visp3/me/vpMeEllipse.h +++ b/modules/tracker/me/include/visp3/me/vpMeEllipse.h @@ -53,6 +53,11 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpMeEllipse * \ingroup module_me @@ -589,4 +594,8 @@ class VISP_EXPORT vpMeEllipse : public vpMeTracker void updateTheta(); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/tracker/me/include/visp3/me/vpMeSite.h b/modules/tracker/me/include/visp3/me/vpMeSite.h index 97e85dac9e..3d0f9871f0 100644 --- a/modules/tracker/me/include/visp3/me/vpMeSite.h +++ b/modules/tracker/me/include/visp3/me/vpMeSite.h @@ -44,6 +44,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpMeSite * \ingroup module_me @@ -392,4 +397,8 @@ class VISP_EXPORT vpMeSite vpMeSiteState m_state; //!< Site state }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/tracker/me/include/visp3/me/vpMeTracker.h b/modules/tracker/me/include/visp3/me/vpMeTracker.h index c96c169ea3..f4e150440b 100644 --- a/modules/tracker/me/include/visp3/me/vpMeTracker.h +++ b/modules/tracker/me/include/visp3/me/vpMeTracker.h @@ -48,6 +48,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpMeTracker * @@ -58,26 +63,6 @@ */ class VISP_EXPORT vpMeTracker : public vpTracker { -protected: - /** @name Protected Attributes Inherited from vpMeTracker */ - //@{ - //! Tracking dependent variables/functions - //! List of tracked moving edges points. - std::list m_meList; - //! Moving edges initialisation parameters - vpMe *m_me; - //! Initial range - unsigned int m_init_range; - //! Number of good moving-edges that are tracked - int m_nGoodElement; - //! Mask used to disable tracking on a part of image - const vpImage *m_mask; - //! Mask used to determine candidate points for initialization in an image - const vpImage *m_maskCandidates; - //! Moving-edges display type - vpMeSite::vpMeSiteDisplayType m_selectDisplay; - //@} - public: /*! * Default constructor. @@ -320,6 +305,31 @@ class VISP_EXPORT vpMeTracker : public vpTracker } //@} #endif + +protected: + /** @name Protected Attributes Inherited from vpMeTracker */ + //@{ + //! Tracking dependent variables/functions + //! List of tracked moving edges points. + std::list m_meList; + //! Moving edges initialisation parameters + vpMe *m_me; + //! Initial range + unsigned int m_init_range; + //! Number of good moving-edges that are tracked + int m_nGoodElement; + //! Mask used to disable tracking on a part of image + const vpImage *m_mask; + //! Mask used to determine candidate points for initialization in an image + const vpImage *m_maskCandidates; + //! Moving-edges display type + vpMeSite::vpMeSiteDisplayType m_selectDisplay; + //@} + }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/tracker/me/src/moving-edges/vpMe.cpp b/modules/tracker/me/src/moving-edges/vpMe.cpp index d89476ca58..93d7278a03 100644 --- a/modules/tracker/me/src/moving-edges/vpMe.cpp +++ b/modules/tracker/me/src/moving-edges/vpMe.cpp @@ -41,6 +41,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #ifndef DOXYGEN_SHOULD_SKIP_THIS namespace { @@ -498,3 +503,7 @@ void vpMe::setMaskSize(const unsigned int &mask_size) m_mask_size = mask_size; initMask(); } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp index 46fbc3896a..11f4c0c94f 100644 --- a/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeEllipse.cpp @@ -40,6 +40,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + // --comment: define the VP_ME_ELLIPSE_REGULAR_SAMPLING flag #ifndef VP_ME_ELLIPSE_REGULAR_SAMPLING #define VP_ME_ELLIPSE_TWO_CONCENTRIC_CIRCLES @@ -1438,3 +1443,7 @@ void vpMeEllipse::displayEllipse(const vpImage &I, const vpImagePoint &c { vpDisplay::displayEllipse(I, center, A, B, E, smallalpha, highalpha, false, color, thickness, true, true); } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/tracker/me/src/moving-edges/vpMeSite.cpp b/modules/tracker/me/src/moving-edges/vpMeSite.cpp index 913805f3ad..56e12aec1c 100644 --- a/modules/tracker/me/src/moving-edges/vpMeSite.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeSite.cpp @@ -43,6 +43,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #ifndef DOXYGEN_SHOULD_SKIP_THIS static bool horsImage(int i, int j, int half, int rows, int cols) { @@ -444,3 +449,7 @@ void vpMeSite::display(const vpImage &I, const double &i, const double & vpDisplay::displayCross(I, vpImagePoint(i, j), 3, vpColor::yellow, 1); } } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/tracker/me/src/moving-edges/vpMeTracker.cpp b/modules/tracker/me/src/moving-edges/vpMeTracker.cpp index dcbc578560..6ff223c362 100644 --- a/modules/tracker/me/src/moving-edges/vpMeTracker.cpp +++ b/modules/tracker/me/src/moving-edges/vpMeTracker.cpp @@ -44,6 +44,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #define DEBUG_LEVEL1 0 #define DEBUG_LEVEL2 0 @@ -291,3 +296,7 @@ void vpMeTracker::display(const vpImage &I, vpColVector &w, unsig #undef DEBUG_LEVEL1 #undef DEBUG_LEVEL2 + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/include/visp3/vision/vpHomography.h b/modules/vision/include/visp3/vision/vpHomography.h index b7bae14eeb..2e5e363bab 100644 --- a/modules/vision/include/visp3/vision/vpHomography.h +++ b/modules/vision/include/visp3/vision/vpHomography.h @@ -51,6 +51,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpHomography * \ingroup group_vision_homography @@ -654,7 +659,7 @@ class VISP_EXPORT vpHomography : public vpArray2D #endif // DOXYGEN_SHOULD_SKIP_THIS private: - static const double m_sing_threshold; // = 0.0001; + static const double m_sing_threshold; /* equals 0.0001 */ static const double m_threshold_rotation; static const double m_threshold_displacement; vpHomogeneousMatrix m_aMb; @@ -698,4 +703,8 @@ class VISP_EXPORT vpHomography : public vpArray2D static void initRansac(unsigned int n, double *xb, double *yb, double *xa, double *ya, vpColVector &x); }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/vision/include/visp3/vision/vpPose.h b/modules/vision/include/visp3/vision/vpPose.h index 83bbfbfd5f..67d6dce801 100644 --- a/modules/vision/include/visp3/vision/vpPose.h +++ b/modules/vision/include/visp3/vision/vpPose.h @@ -62,6 +62,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpPose * \ingroup group_vision_pose @@ -125,7 +130,7 @@ class VISP_EXPORT vpPose /*! * Constructor from a vector of points. */ - vpPose(const std::vector &lP); + explicit vpPose(const std::vector &lP); /*! * Destructor that deletes the array of point (freed the memory). @@ -406,7 +411,7 @@ class VISP_EXPORT vpPose /*! * Get the number of inliers. */ - unsigned int getRansacNbInliers() const { return (unsigned int)ransacInliers.size(); } + unsigned int getRansacNbInliers() const { return static_cast(ransacInliers.size()); } /** * Get the vector of indexes corresponding to inliers. @@ -437,10 +442,10 @@ class VISP_EXPORT vpPose */ vpMatrix getCovarianceMatrix() const { - if (!computeCovariance) + if (!computeCovariance) { vpTRACE("Warning : The covariance matrix has not been computed. See " "setCovarianceComputation() to do it."); - + } return covarianceMatrix; } @@ -693,7 +698,7 @@ class VISP_EXPORT vpPose const std::map &ips, const vpCameraParameters &camera_intrinsics, std::optional cMo_init = std::nullopt, bool enable_vvs = true) { - if (cMo_init && !enable_vvs) { + if (cMo_init && (!enable_vvs)) { throw(vpException( vpException::fatalError, "It doesn't make sense to use an initialized pose without enabling VVS to compute the pose from 4 points")); @@ -881,4 +886,8 @@ class VISP_EXPORT vpPose }; }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/vision/include/visp3/vision/vpPoseException.h b/modules/vision/include/visp3/vision/vpPoseException.h index ed749e1d82..de51ec66ad 100644 --- a/modules/vision/include/visp3/vision/vpPoseException.h +++ b/modules/vision/include/visp3/vision/vpPoseException.h @@ -39,6 +39,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * \class vpPoseException * \ingroup group_vision_pose @@ -89,4 +94,8 @@ class VISP_EXPORT vpPoseException : public vpException explicit vpPoseException(int id) : vpException(id) { } }; +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/vision/src/homography-estimation/vpHomography.cpp b/modules/vision/src/homography-estimation/vpHomography.cpp index 9b9dd5d1ff..48c344c589 100644 --- a/modules/vision/src/homography-estimation/vpHomography.cpp +++ b/modules/vision/src/homography-estimation/vpHomography.cpp @@ -48,6 +48,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + vpHomography::vpHomography() : vpArray2D(3, 3), m_aMb(), m_bP() { eye(); } vpHomography::vpHomography(const vpHomography &H) : vpArray2D(3, 3), m_aMb(), m_bP() { *this = H; } @@ -713,3 +718,7 @@ vpHomography vpHomography::homography2collineation(const vpCameraParameters &cam return H; } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/src/homography-estimation/vpHomographyDLT.cpp b/modules/vision/src/homography-estimation/vpHomographyDLT.cpp index 7025c9f5c5..66d3f8d8f3 100644 --- a/modules/vision/src/homography-estimation/vpHomographyDLT.cpp +++ b/modules/vision/src/homography-estimation/vpHomographyDLT.cpp @@ -45,6 +45,11 @@ #include // std::fabs #include // numeric_limits +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #ifndef DOXYGEN_SHOULD_SKIP_THIS void vpHomography::hartleyNormalization(const std::vector &x, const std::vector &y, @@ -308,3 +313,7 @@ void vpHomography::DLT(const std::vector &xb, const std::vector aHb = aHbn; } } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/src/homography-estimation/vpHomographyExtract.cpp b/modules/vision/src/homography-estimation/vpHomographyExtract.cpp index 3af2843954..b238259ec1 100644 --- a/modules/vision/src/homography-estimation/vpHomographyExtract.cpp +++ b/modules/vision/src/homography-estimation/vpHomographyExtract.cpp @@ -35,6 +35,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + //#define DEBUG_Homographie 0 /* ---------------------------------------------------------------------- */ @@ -137,28 +142,33 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, const vpColVecto vOrdre[0] = 0; vOrdre[1] = 1; vOrdre[2] = 2; - } else { + } + else { vOrdre[0] = 0; vOrdre[1] = 2; vOrdre[2] = 1; } - } else { + } + else { vOrdre[0] = 2; vOrdre[1] = 0; vOrdre[2] = 1; } - } else { + } + else { if (svTemp[1] >= svTemp[2]) { if (svTemp[0] > svTemp[2]) { vOrdre[0] = 1; vOrdre[1] = 0; vOrdre[2] = 2; - } else { + } + else { vOrdre[0] = 1; vOrdre[1] = 2; vOrdre[2] = 0; } - } else { + } + else { vOrdre[0] = 2; vOrdre[1] = 1; vOrdre[2] = 0; @@ -220,7 +230,8 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, const vpColVecto n[0] = normaleDesiree[0]; n[1] = normaleDesiree[1]; n[2] = normaleDesiree[2]; - } else { + } + else { #ifdef DEBUG_Homographie printf("\nCas general\n"); #endif @@ -318,7 +329,7 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, const vpColVecto de la solution retenue (cf. ci-dessous) *****/ sinusTheta = - (signeSinus * sqrt(((sv[0] * sv[0]) - (sv[1] * sv[1])) * ((sv[1] * sv[1]) - (sv[2] * sv[2])))) / ((sv[0] + sv[2]) * sv[1]); + (signeSinus * sqrt(((sv[0] * sv[0]) - (sv[1] * sv[1])) * ((sv[1] * sv[1]) - (sv[2] * sv[2])))) / ((sv[0] + sv[2]) * sv[1]); cosinusTheta = ((sv[1] * sv[1]) + (sv[0] * sv[2])) / ((sv[0] + sv[2]) * sv[1]); @@ -434,28 +445,33 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, vpRotationMatrix vOrdre[0] = 0; vOrdre[1] = 1; vOrdre[2] = 2; - } else { + } + else { vOrdre[0] = 0; vOrdre[1] = 2; vOrdre[2] = 1; } - } else { + } + else { vOrdre[0] = 2; vOrdre[1] = 0; vOrdre[2] = 1; } - } else { + } + else { if (svTemp[1] >= svTemp[2]) { if (svTemp[0] > svTemp[2]) { vOrdre[0] = 1; vOrdre[1] = 0; vOrdre[2] = 2; - } else { + } + else { vOrdre[0] = 1; vOrdre[1] = 2; vOrdre[2] = 0; } - } else { + } + else { vOrdre[0] = 2; vOrdre[1] = 1; vOrdre[2] = 0; @@ -517,7 +533,8 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, vpRotationMatrix n[0] = normaleDesiree[0]; n[1] = normaleDesiree[1]; n[2] = normaleDesiree[2]; - } else { + } + else { #ifdef DEBUG_Homographie printf("\nCas general\n"); #endif @@ -550,7 +567,7 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, vpRotationMatrix for (unsigned int i = 0; i < 3; ++i) { normaleEstimee[i] = 0.0; for (unsigned int j = 0; j < 3; ++j) { - normaleEstimee[i] += ((2.0 * k )- 1.0) * mV[i][j] * mX[j][w]; + normaleEstimee[i] += ((2.0 * k)- 1.0) * mV[i][j] * mX[j][w]; } } @@ -615,7 +632,7 @@ void vpHomography::computeDisplacement(const vpHomography &aHb, vpRotationMatrix de la solution retenue (cf. ci-dessous) *****/ sinusTheta = - (signeSinus * sqrt(((sv[0] * sv[0]) - (sv[1] * sv[1])) * ((sv[1] * sv[1]) - (sv[2] * sv[2])))) / ((sv[0] + sv[2]) * sv[1]); + (signeSinus * sqrt(((sv[0] * sv[0]) - (sv[1] * sv[1])) * ((sv[1] * sv[1]) - (sv[2] * sv[2])))) / ((sv[0] + sv[2]) * sv[1]); cosinusTheta = ((sv[1] * sv[1]) + (sv[0] * sv[2])) / ((sv[0] + sv[2]) * sv[1]); @@ -713,28 +730,33 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y vOrdre[0] = 0; vOrdre[1] = 1; vOrdre[2] = 2; - } else { + } + else { vOrdre[0] = 0; vOrdre[1] = 2; vOrdre[2] = 1; } - } else { + } + else { vOrdre[0] = 2; vOrdre[1] = 0; vOrdre[2] = 1; } - } else { + } + else { if (svTemp[1] >= svTemp[2]) { if (svTemp[0] > svTemp[2]) { vOrdre[0] = 1; vOrdre[1] = 0; vOrdre[2] = 2; - } else { + } + else { vOrdre[0] = 1; vOrdre[1] = 2; vOrdre[2] = 0; } - } else { + } + else { vOrdre[0] = 2; vOrdre[1] = 1; vOrdre[2] = 0; @@ -764,10 +786,10 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // calcul du determinant de U et V determinantU = (U[0][0] * ((U[1][1] * U[2][2]) - (U[1][2] * U[2][1]))) + (U[0][1] * ((U[1][2] * U[2][0]) - (U[1][0] * U[2][2]))) + - (U[0][2] * ((U[1][0] * U[2][1]) - (U[1][1] * U[2][0]))); + (U[0][2] * ((U[1][0] * U[2][1]) - (U[1][1] * U[2][0]))); determinantV = (V[0][0] * ((V[1][1] * V[2][2]) - (V[1][2] * V[2][1]))) + (V[0][1] * ((V[1][2] * V[2][0]) - (V[1][0] * V[2][2]))) + - (V[0][2] * ((V[1][0] * V[2][1]) - (V[1][1] * V[2][0]))); + (V[0][2] * ((V[1][0] * V[2][1]) - (V[1][1] * V[2][0]))); s = determinantU * determinantV; @@ -807,7 +829,8 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y else { cas = cas2; } - } else { + } + else { if ((sv[1] - sv[2]) < m_sing_threshold) { cas = cas3; } @@ -930,7 +953,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim1[2][0] = (sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] + sv[2]) * sv[1]); + ((sv[0] + sv[2]) * sv[1]); Rprim1[0][2] = -Rprim1[2][0]; @@ -952,7 +975,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim2[2][0] = -(sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] + sv[2]) * sv[1]); + ((sv[0] + sv[2]) * sv[1]); Rprim2[0][2] = -Rprim2[2][0]; @@ -974,7 +997,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim3[2][0] = -(sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] + sv[2]) * sv[1]); + ((sv[0] + sv[2]) * sv[1]); Rprim3[0][2] = -Rprim3[2][0]; @@ -996,7 +1019,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim4[2][0] = (sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] + sv[2]) * sv[1]); + ((sv[0] + sv[2]) * sv[1]); Rprim4[0][2] = -Rprim4[2][0]; @@ -1061,7 +1084,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim1[2][0] = (sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] - sv[2]) * sv[1]); + ((sv[0] - sv[2]) * sv[1]); Rprim1[0][2] = Rprim1[2][0]; @@ -1083,7 +1106,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim2[2][0] = -(sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] - sv[2]) * sv[1]); + ((sv[0] - sv[2]) * sv[1]); Rprim2[0][2] = Rprim2[2][0]; @@ -1105,7 +1128,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim3[2][0] = -(sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] - sv[2]) * sv[1]); + ((sv[0] - sv[2]) * sv[1]); Rprim3[0][2] = Rprim3[2][0]; @@ -1126,7 +1149,7 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y // sin theta Rprim4[2][0] = (sqrt((vpMath::sqr(sv[0]) - vpMath::sqr(sv[1])) * (vpMath::sqr(sv[1]) - vpMath::sqr(sv[2])))) / - ((sv[0] - sv[2]) * sv[1]); + ((sv[0] - sv[2]) * sv[1]); Rprim4[0][2] = Rprim4[2][0]; @@ -1232,14 +1255,15 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y vT.push_back(T4); vN.push_back(N4); } - } else { + } + else { std::cout << "On tombe dans le cas particulier ou le mouvement n'est pas " - "estimable!" - << std::endl; + "estimable!" + << std::endl; } - #ifdef DEBUG_Homographie - // on peut ensuite afficher les resultats... +#ifdef DEBUG_Homographie +// on peut ensuite afficher les resultats... std::cout << "Analyse des resultats : "<< std::endl; if (cas==cas1) { std::cout << "On est dans le cas 1" << std::endl; @@ -1260,10 +1284,14 @@ void vpHomography::computeDisplacement(const vpHomography &H, double x, double y else { std::cout << "d'>0" << std::endl; } - #endif +#endif #ifdef DEBUG_Homographie printf("fin : Homographie_EstimationDeplacementCamera\n"); #endif } #endif //#ifndef DOXYGEN_SHOULD_SKIP_THIS + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/src/homography-estimation/vpHomographyMalis.cpp b/modules/vision/src/homography-estimation/vpHomographyMalis.cpp index 69fb836691..f587e34d96 100644 --- a/modules/vision/src/homography-estimation/vpHomographyMalis.cpp +++ b/modules/vision/src/homography-estimation/vpHomographyMalis.cpp @@ -49,6 +49,10 @@ #include // std::fabs #include // numeric_limits +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif #ifndef DOXYGEN_SHOULD_SKIP_THIS namespace @@ -623,7 +627,11 @@ void vpHomography::HLM(const std::vector &xb, const std::vector q_cible = 3; } - ::hlm(q_cible, xa, ya, xb, yb, H); + hlm(q_cible, xa, ya, xb, yb, H); aHb = H; } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/src/homography-estimation/vpHomographyRansac.cpp b/modules/vision/src/homography-estimation/vpHomographyRansac.cpp index bd0e5fae50..ad2e2c6f3b 100644 --- a/modules/vision/src/homography-estimation/vpHomographyRansac.cpp +++ b/modules/vision/src/homography-estimation/vpHomographyRansac.cpp @@ -39,6 +39,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #define VPEPS 1e-6 /*! @@ -528,3 +533,7 @@ bool vpHomography::ransac(const std::vector &xb, const std::vector #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + const double vpHomography::m_threshold_rotation = 1e-7; const double vpHomography::m_threshold_displacement = 1e-18; @@ -696,3 +701,7 @@ double vpHomography::computeDisplacement(unsigned int nbpoint, vpPoint *c1P, vpP } #endif //#ifndef DOXYGEN_SHOULD_SKIP_THIS + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp index a6e091c56e..4de8e57cbc 100644 --- a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp +++ b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.cpp @@ -39,6 +39,11 @@ #include #include "vpLevenbergMarquartd.h" +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #define SIGN(x) ((x) < 0 ? -1 : 1) #define SWAP(a, b, c) \ { \ @@ -1205,3 +1210,7 @@ int lmder1(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, double *jac, #undef TRUE #undef FALSE + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.h b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.h index 768dcba371..5ab0e298d0 100644 --- a/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.h +++ b/modules/vision/src/pose-estimation/private/vpLevenbergMarquartd.h @@ -43,6 +43,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + /*! * ENTREE : * n Ordre de la matrice "r". @@ -459,4 +464,8 @@ int VISP_EXPORT lmder1(void (*ptr_fcn)(int m, int n, double *xc, double *fvecc, int m, int n, double *x, double *fvec, double *fjac, int ldfjac, double tol, int *info, int *ipvt, int lwa, double *wa); +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif + #endif diff --git a/modules/vision/src/pose-estimation/vpPose.cpp b/modules/vision/src/pose-estimation/vpPose.cpp index 10ecac0f53..787d09752e 100644 --- a/modules/vision/src/pose-estimation/vpPose.cpp +++ b/modules/vision/src/pose-estimation/vpPose.cpp @@ -49,6 +49,11 @@ #include // std::fabs #include // numeric_limits +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #define DEBUG_LEVEL1 0 vpPose::vpPose() @@ -331,7 +336,8 @@ double vpPose::computeResidual(const vpHomogeneousMatrix &cMo, const vpCameraPar vpMeterPixelConversion::convertPoint(cam, P.get_x(), P.get_y(), u_moved, v_moved); double squaredResidual = vpMath::sqr(u_moved - u_initial) + vpMath::sqr(v_moved - v_initial); - residuals[i++] = squaredResidual; + residuals[i] = squaredResidual; + i++; squared_error += squaredResidual; } return squared_error; @@ -662,3 +668,7 @@ double vpPose::poseFromRectangle(vpPoint &p1, vpPoint &p2, vpPoint &p3, vpPoint P.computePose(vpPose::DEMENTHON_LOWE, cMo); return lx / s; } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/src/pose-estimation/vpPoseDementhon.cpp b/modules/vision/src/pose-estimation/vpPoseDementhon.cpp index cfa8763aeb..2fcc251d59 100644 --- a/modules/vision/src/pose-estimation/vpPoseDementhon.cpp +++ b/modules/vision/src/pose-estimation/vpPoseDementhon.cpp @@ -34,6 +34,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #define DEBUG_LEVEL1 0 #define DEBUG_LEVEL2 0 #define DEBUG_LEVEL3 0 @@ -612,3 +617,7 @@ double vpPose::computeResidualDementhon(const vpHomogeneousMatrix &cMo) #undef DEBUG_LEVEL1 #undef DEBUG_LEVEL2 #undef DEBUG_LEVEL3 + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/src/pose-estimation/vpPoseLagrange.cpp b/modules/vision/src/pose-estimation/vpPoseLagrange.cpp index e0d778dbac..98a4542fda 100644 --- a/modules/vision/src/pose-estimation/vpPoseLagrange.cpp +++ b/modules/vision/src/pose-estimation/vpPoseLagrange.cpp @@ -33,6 +33,11 @@ #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #define DEBUG_LEVEL1 0 #define DEBUG_LEVEL2 0 @@ -586,3 +591,7 @@ void vpPose::poseLagrangeNonPlan(vpHomogeneousMatrix &cMo) #undef DEBUG_LEVEL1 #undef DEBUG_LEVEL2 + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/src/pose-estimation/vpPoseLowe.cpp b/modules/vision/src/pose-estimation/vpPoseLowe.cpp index 1544b01bcc..79d9a55e2d 100644 --- a/modules/vision/src/pose-estimation/vpPoseLowe.cpp +++ b/modules/vision/src/pose-estimation/vpPoseLowe.cpp @@ -41,6 +41,11 @@ #include "private/vpLevenbergMarquartd.h" #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + #define NBR_PAR 6 #define X3_SIZE 3 #define MINIMUM 0.000001 @@ -329,3 +334,7 @@ void vpPose::poseLowe(vpHomogeneousMatrix &cMo) #undef MINIMUM #undef DEBUG_LEVEL1 + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/src/pose-estimation/vpPoseRGBD.cpp b/modules/vision/src/pose-estimation/vpPoseRGBD.cpp index bd519fccc4..c9af47f58f 100644 --- a/modules/vision/src/pose-estimation/vpPoseRGBD.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRGBD.cpp @@ -37,8 +37,11 @@ #include #include -namespace +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp { +#endif + // See also vpPlaneEstimation.cpp that implements the same functionaly in c++17 void estimatePlaneEquationSVD(const std::vector &point_cloud_face, vpPlane &plane_equation_estimated, vpColVector ¢roid, double &normalized_weights) @@ -146,8 +149,6 @@ void estimatePlaneEquationSVD(const std::vector &point_cloud_face, vpPla normalized_weights = total_w / nPoints; } -} // namespace - bool vpPose::computePlanarObjectPoseFromRGBD(const vpImage &depthMap, const std::vector &corners, const vpCameraParameters &colorIntrinsics, const std::vector &point3d, vpHomogeneousMatrix &cMo, @@ -445,3 +446,7 @@ bool vpPose::computePlanarObjectPoseFromRGBD(const vpImage &depthMap, } return false; } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/src/pose-estimation/vpPoseRansac.cpp b/modules/vision/src/pose-estimation/vpPoseRansac.cpp index 89ebc2ffb8..a0f6c5ea7e 100644 --- a/modules/vision/src/pose-estimation/vpPoseRansac.cpp +++ b/modules/vision/src/pose-estimation/vpPoseRansac.cpp @@ -53,6 +53,10 @@ #include #endif +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif #define EPS 1e-6 namespace @@ -592,3 +596,7 @@ void vpPose::findMatch(std::vector &p2D, std::vector &p3D, listInliers = pose.getRansacInliers(); } } + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif diff --git a/modules/vision/src/pose-estimation/vpPoseVirtualVisualServoing.cpp b/modules/vision/src/pose-estimation/vpPoseVirtualVisualServoing.cpp index 5a47dd1103..7727de8106 100644 --- a/modules/vision/src/pose-estimation/vpPoseVirtualVisualServoing.cpp +++ b/modules/vision/src/pose-estimation/vpPoseVirtualVisualServoing.cpp @@ -42,6 +42,11 @@ #include #include +#if defined(ENABLE_VISP_NAMESPACE) +namespace visp +{ +#endif + void vpPose::poseVirtualVS(vpHomogeneousMatrix &cMo) { try { @@ -354,3 +359,7 @@ std::optional vpPose::poseVirtualVSWithDepth(const std::vec } #endif + +#if defined(ENABLE_VISP_NAMESPACE) +} +#endif