From cb55ec86d296d924e5ab9481a8a9b99e988d3a75 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 9 Dec 2021 11:07:10 -0600 Subject: [PATCH 1/9] Convert ign-math to use implptr where relevant Signed-off-by: Michael Carroll --- CMakeLists.txt | 5 ++ include/ignition/math/AxisAlignedBox.hh | 19 +--- include/ignition/math/Box.hh | 7 -- include/ignition/math/Cylinder.hh | 3 - include/ignition/math/DiffDriveOdometry.hh | 20 +---- include/ignition/math/Frustum.hh | 19 +--- include/ignition/math/GaussMarkovProcess.hh | 20 +---- include/ignition/math/Kmeans.hh | 11 +-- include/ignition/math/Material.hh | 28 +----- include/ignition/math/RollingMean.hh | 20 +---- include/ignition/math/RotationSpline.hh | 10 +-- include/ignition/math/SemanticVersion.hh | 31 +------ include/ignition/math/SignalStats.hh | 54 ++---------- include/ignition/math/Sphere.hh | 3 - include/ignition/math/SphericalCoordinates.hh | 29 +----- include/ignition/math/Spline.hh | 7 +- include/ignition/math/Stopwatch.hh | 39 +------- include/ignition/math/Temperature.hh | 40 +-------- include/ignition/math/Vector3Stats.hh | 10 +-- src/AxisAlignedBox.cc | 33 +------ src/Box_TEST.cc | 18 ++++ src/CMakeLists.txt | 70 ++------------- src/DiffDriveOdometry.cc | 14 ++- src/Frustum.cc | 81 ++++++++++------- src/FrustumPrivate.hh | 88 ------------------- src/GaussMarkovProcess.cc | 11 +-- src/Kmeans.cc | 9 +- src/KmeansPrivate.hh | 2 +- src/Material.cc | 51 ++--------- src/Material_TEST.cc | 2 - src/RollingMean.cc | 9 +- src/RotationSpline.cc | 23 +++-- src/RotationSplinePrivate.cc | 26 ------ src/RotationSplinePrivate.hh | 50 ----------- src/SemanticVersion.cc | 27 +----- src/SignalStats.cc | 32 +------ src/SignalStatsPrivate.hh | 22 +---- src/SphericalCoordinates.cc | 36 +------- src/Spline.cc | 16 +--- src/SplinePrivate.cc | 9 -- src/SplinePrivate.hh | 27 +++--- src/Stopwatch.cc | 49 +---------- src/Temperature.cc | 42 ++------- src/Vector3Stats.cc | 24 +++-- src/Vector3StatsPrivate.hh | 48 ---------- 45 files changed, 202 insertions(+), 992 deletions(-) delete mode 100644 src/FrustumPrivate.hh delete mode 100644 src/RotationSplinePrivate.cc delete mode 100644 src/RotationSplinePrivate.hh delete mode 100644 src/Vector3StatsPrivate.hh diff --git a/CMakeLists.txt b/CMakeLists.txt index 9d2ef7eb7..c4ce82f75 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -28,6 +28,11 @@ ign_configure_project(VERSION_SUFFIX pre1) # Search for project-specific dependencies #============================================================================ +#-------------------------------------- +# Find ignition-utils +ign_find_package(ignition-utils1 REQUIRED VERSION 1.0) +set(IGN_UTILS_VER ${ignition-utils1_VERSION_MAJOR}) + #-------------------------------------- # Find eigen3 ign_find_package( diff --git a/include/ignition/math/AxisAlignedBox.hh b/include/ignition/math/AxisAlignedBox.hh index 19bb8ce2e..ab40b02ef 100644 --- a/include/ignition/math/AxisAlignedBox.hh +++ b/include/ignition/math/AxisAlignedBox.hh @@ -25,6 +25,7 @@ #include #include #include +#include namespace ignition { @@ -32,10 +33,6 @@ namespace ignition { // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - // Forward declaration of private data - class AxisAlignedBoxPrivate; - /// \class AxisAlignedBox AxisAlignedBox.hh ignition/math/AxisAlignedBox.hh /// \brief Mathematical representation of a box that is aligned along /// an X,Y,Z axis. @@ -66,13 +63,6 @@ namespace ignition public: AxisAlignedBox(double _vec1X, double _vec1Y, double _vec1Z, double _vec2X, double _vec2Y, double _vec2Z); - /// \brief Copy Constructor - /// \param[in] _b AxisAlignedBox to copy - public: AxisAlignedBox(const AxisAlignedBox &_b); - - /// \brief Destructor - public: ~AxisAlignedBox(); - /// \brief Get the length along the x dimension /// \return Double value of the length in the x dimension public: double XLength() const; @@ -97,11 +87,6 @@ namespace ignition /// \param[in] _box AxisAlignedBox to add to this box public: void Merge(const AxisAlignedBox &_box); - /// \brief Assignment operator. Set this box to the parameter - /// \param[in] _b AxisAlignedBox to copy - /// \return The new box. - public: AxisAlignedBox &operator=(const AxisAlignedBox &_b); - /// \brief Addition operator. result = this + _b /// \param[in] _b AxisAlignedBox to add /// \return The new box @@ -287,7 +272,7 @@ namespace ignition double &_low, double &_high) const; /// \brief Private data pointer - private: AxisAlignedBoxPrivate *dataPtr; + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/Box.hh b/include/ignition/math/Box.hh index 86990fdfe..87ea16e71 100644 --- a/include/ignition/math/Box.hh +++ b/include/ignition/math/Box.hh @@ -82,13 +82,6 @@ namespace ignition public: Box(const Vector3 &_size, const ignition::math::Material &_mat); - /// \brief Copy Constructor. - /// \param[in] _b Box to copy. - public: Box(const Box &_b) = default; - - /// \brief Destructor. - public: ~Box() = default; - /// \brief Get the size of the box. /// \return Size of the box in meters. public: math::Vector3 Size() const; diff --git a/include/ignition/math/Cylinder.hh b/include/ignition/math/Cylinder.hh index 31a2eacca..34dc6561e 100644 --- a/include/ignition/math/Cylinder.hh +++ b/include/ignition/math/Cylinder.hh @@ -67,9 +67,6 @@ namespace ignition const Quaternion &_rotOffset = Quaternion::Identity); - /// \brief Destructor - public: ~Cylinder() = default; - /// \brief Get the radius in meters. /// \return The radius of the cylinder in meters. public: Precision Radius() const; diff --git a/include/ignition/math/DiffDriveOdometry.hh b/include/ignition/math/DiffDriveOdometry.hh index 93d272155..7a5884fd8 100644 --- a/include/ignition/math/DiffDriveOdometry.hh +++ b/include/ignition/math/DiffDriveOdometry.hh @@ -18,10 +18,10 @@ #define IGNITION_MATH_DIFFDRIVEODOMETRY_HH_ #include -#include #include #include #include +#include namespace ignition { @@ -32,10 +32,6 @@ namespace ignition // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - // Forward declarations. - class DiffDriveOdometryPrivate; - /** \class DiffDriveOdometry DiffDriveOdometry.hh \ * ignition/math/DiffDriveOdometry.hh **/ @@ -85,9 +81,6 @@ namespace ignition /// velocity mean public: explicit DiffDriveOdometry(size_t _windowSize = 10); - /// \brief Destructor. - public: ~DiffDriveOdometry(); - /// \brief Initialize the odometry /// \param[in] _time Current time. public: void Init(const clock::time_point &_time); @@ -136,17 +129,8 @@ namespace ignition /// \param[in] _size The Velocity rolling window size. public: void SetVelocityRollingWindowSize(size_t _size); -#ifdef _WIN32 -// Disable warning C4251 which is triggered by -// std::unique_ptr -#pragma warning(push) -#pragma warning(disable: 4251) -#endif /// \brief Private data pointer. - private: std::unique_ptr dataPtr; -#ifdef _WIN32 -#pragma warning(pop) -#endif + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/Frustum.hh b/include/ignition/math/Frustum.hh index b85e23f2a..a96fd11d9 100644 --- a/include/ignition/math/Frustum.hh +++ b/include/ignition/math/Frustum.hh @@ -22,6 +22,7 @@ #include #include #include +#include namespace ignition { @@ -29,9 +30,6 @@ namespace ignition { // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - // Forward declaration of private data - class FrustumPrivate; /// \brief Mathematical representation of a frustum and related functions. /// This is also known as a view frustum. @@ -86,13 +84,6 @@ namespace ignition const double _aspectRatio, const math::Pose3d &_pose = math::Pose3d::Zero); - /// \brief Copy Constructor - /// \param[in] _p Frustum to copy. - public: Frustum(const Frustum &_p); - - /// \brief Destructor - public: ~Frustum(); - /// \brief Get the near distance. This is the distance from the /// frustum's vertex to the closest plane. /// \return Near distance. @@ -168,18 +159,12 @@ namespace ignition /// \sa Pose public: void SetPose(const Pose3d &_pose); - /// \brief Assignment operator. Set this frustum to the parameter. - /// \param[in] _f Frustum to copy - /// \return The new frustum. - public: Frustum &operator=(const Frustum &_f); - /// \brief Compute the planes of the frustum. This is called whenever /// a property of the frustum is changed. private: void ComputePlanes(); - /// \internal /// \brief Private data pointer - private: FrustumPrivate *dataPtr; + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/GaussMarkovProcess.hh b/include/ignition/math/GaussMarkovProcess.hh index 02ebb1a4f..c048309fe 100644 --- a/include/ignition/math/GaussMarkovProcess.hh +++ b/include/ignition/math/GaussMarkovProcess.hh @@ -18,9 +18,9 @@ #define IGNITION_MATH_GAUSSMARKOVPROCESS_HH_ #include -#include #include #include +#include namespace ignition { @@ -31,10 +31,6 @@ namespace ignition // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - // Forward declarations. - class GaussMarkovProcessPrivate; - /** \class GaussMarkovProcess GaussMarkovProcess.hh\ * ignition/math/GaussMarkovProcess.hh **/ @@ -64,9 +60,6 @@ namespace ignition public: GaussMarkovProcess(double _start, double _theta, double _mu, double _sigma); - /// \brief Destructor. - public: ~GaussMarkovProcess(); - /// \brief Set the process parameters. This will also call Reset(). /// \param[in] _start The start value of the process. /// \param[in] _theta The theta (\f$\theta\f$) parameter. @@ -135,17 +128,8 @@ namespace ignition public: double Update(double _dt); -#ifdef _WIN32 -// Disable warning C4251 which is triggered by -// std::unique_ptr -#pragma warning(push) -#pragma warning(disable: 4251) -#endif /// \brief Private data pointer. - private: std::unique_ptr dataPtr; -#ifdef _WIN32 -#pragma warning(pop) -#endif + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/Kmeans.hh b/include/ignition/math/Kmeans.hh index 43d4231d4..585685edc 100644 --- a/include/ignition/math/Kmeans.hh +++ b/include/ignition/math/Kmeans.hh @@ -22,15 +22,14 @@ #include #include +#include + namespace ignition { namespace math { // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - // Forward declare private data - class KmeansPrivate; /// \class Kmeans Kmeans.hh math/gzmath.hh /// \brief K-Means clustering algorithm. Given a set of observations, @@ -43,9 +42,6 @@ namespace ignition /// \param[in] _obs Set of observations to cluster. public: explicit Kmeans(const std::vector &_obs); - /// \brief Destructor. - public: virtual ~Kmeans(); - /// \brief Get the observations to cluster. /// \return The vector of observations. public: std::vector Observations() const; @@ -80,8 +76,7 @@ namespace ignition /// \return The index of the closest centroid to the point _p. private: unsigned int ClosestCentroid(const Vector3d &_p) const; - /// \brief Private data pointer - private: KmeansPrivate *dataPtr; + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/Material.hh b/include/ignition/math/Material.hh index 89bde08ea..061baeef2 100644 --- a/include/ignition/math/Material.hh +++ b/include/ignition/math/Material.hh @@ -23,6 +23,7 @@ #include #include #include +#include namespace ignition { @@ -30,8 +31,6 @@ namespace ignition { // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // Forward declarations - class MaterialPrivate; /// \brief Contains information about a single material. /// @@ -80,18 +79,6 @@ namespace ignition /// \param[in] _density Material density. public: explicit Material(const double _density); - /// \brief Copy constructor. - /// \param[in] _material Material to copy. - public: Material(const Material &_material); - - /// \brief Move constructor. - /// \param[in] _material Material to move. The _material object will - /// have default values after the move. - public: Material(Material &&_material); - - /// \brief Destructor. - public: ~Material(); - /// \brief Get all the built-in materials. /// \return A map of all the materials. The map's key is /// material type and the map's value is the material object. @@ -107,17 +94,6 @@ namespace ignition const double _value, const double _epsilon = std::numeric_limits::max()); - /// \brief Copy operator. - /// \param[in] _material Material to copy. - /// \return Reference to this material. - public: Material &operator=(const Material &_material); - - /// \brief Move operator. - /// \param[in] _material Material to move. The _material object will - /// contain default values after this move. - /// \return Reference to this Material. - public: Material &operator=(Material &&_material); - /// \brief Equality operator. This compares type and density values. /// \param[in] _material Material to evaluate this object against. /// \return True if this material is equal to the given _material. @@ -158,7 +134,7 @@ namespace ignition public: void SetDensity(const double _density); /// \brief Private data pointer. - private: MaterialPrivate *dataPtr = nullptr; + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/RollingMean.hh b/include/ignition/math/RollingMean.hh index ff49dbdec..6b3f3f96b 100644 --- a/include/ignition/math/RollingMean.hh +++ b/include/ignition/math/RollingMean.hh @@ -17,9 +17,9 @@ #ifndef IGNITION_MATH_ROLLINGMEAN_HH_ #define IGNITION_MATH_ROLLINGMEAN_HH_ -#include #include #include +#include namespace ignition { @@ -27,10 +27,6 @@ namespace ignition { // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - // Forward declarations. - class RollingMeanPrivate; - /// \brief A class that computes the mean over a series of data points. /// The window size determines the maximum number of data points. The /// oldest value is popped off when the window size is reached and @@ -42,9 +38,6 @@ namespace ignition /// ignored if it is equal to zero. public: explicit RollingMean(size_t _windowSize = 10); - /// \brief Destructor. - public: ~RollingMean(); - /// \brief Get the mean value. /// \return The current mean value, or /// std::numeric_limits::quiet_NaN() if data points are not @@ -71,17 +64,8 @@ namespace ignition /// \return The window size. public: size_t WindowSize() const; -#ifdef _WIN32 -// Disable warning C4251 which is triggered by -// std::unique_ptr -#pragma warning(push) -#pragma warning(disable: 4251) -#endif /// \brief Private data pointer. - private: std::unique_ptr dataPtr; -#ifdef _WIN32 -#pragma warning(pop) -#endif + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/RotationSpline.hh b/include/ignition/math/RotationSpline.hh index 4c4c6b8d9..7ca354855 100644 --- a/include/ignition/math/RotationSpline.hh +++ b/include/ignition/math/RotationSpline.hh @@ -19,6 +19,7 @@ #include #include +#include namespace ignition { @@ -26,10 +27,6 @@ namespace ignition { // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - // Forward declare private data - class RotationSplinePrivate; - /// \class RotationSpline RotationSpline.hh ignition/math/RotationSpline.hh /// \brief Spline for rotations class IGNITION_MATH_VISIBLE RotationSpline @@ -37,9 +34,6 @@ namespace ignition /// \brief Constructor. Sets the autoCalc to true public: RotationSpline(); - /// \brief Destructor. Nothing is done - public: ~RotationSpline(); - /// \brief Adds a control point to the end of the spline. /// \param[in] _p control point public: void AddPoint(const Quaterniond &_p); @@ -117,7 +111,7 @@ namespace ignition public: void RecalcTangents(); /// \brief Private data pointer - private: RotationSplinePrivate *dataPtr; + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/SemanticVersion.hh b/include/ignition/math/SemanticVersion.hh index 0c6e4c890..9042aa823 100644 --- a/include/ignition/math/SemanticVersion.hh +++ b/include/ignition/math/SemanticVersion.hh @@ -18,10 +18,11 @@ #ifndef IGNITION_MATH_SEMANTICVERSION_HH_ #define IGNITION_MATH_SEMANTICVERSION_HH_ -#include +#include #include #include #include +#include namespace ignition { @@ -29,10 +30,6 @@ namespace ignition { // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - // Forward declare private data class - class SemanticVersionPrivate; - /// \class SemanticVersion SemanticVersion.hh /// ignition/math/SemanticVersion.hh /// \brief Version comparison class based on Semantic Versioning 2.0.0 @@ -48,15 +45,6 @@ namespace ignition /// \param[in] _v the string version. ex: "0.3.2" public: explicit SemanticVersion(const std::string &_v); - /// \brief Copy constructor - /// \param[in] _copy the other version - public: SemanticVersion(const SemanticVersion &_copy); - - /// \brief Assignment operator - /// \param[in] _other The version to assign from. - /// \return The reference to this instance - public: SemanticVersion &operator=(const SemanticVersion &_other); - /// \brief Constructor /// \param[in] _major The major number /// \param[in] _minor The minor number @@ -69,9 +57,6 @@ namespace ignition const std::string &_prerelease = "", const std::string &_build = ""); - /// \brief Destructor - public: ~SemanticVersion(); - /// \brief Parse a version string and set the major, minor, patch /// numbers, and prerelease and build strings. /// \param[in] _versionStr The version string, such as "1.2.3-pr+123" @@ -146,17 +131,7 @@ namespace ignition return _out; } -#ifdef _WIN32 -// Disable warning C4251 which is triggered by -// std::unique_ptr -#pragma warning(push) -#pragma warning(disable: 4251) -#endif - /// \brief Pointer to private data - private: std::unique_ptr dataPtr; -#ifdef _WIN32 -#pragma warning(pop) -#endif + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/SignalStats.hh b/include/ignition/math/SignalStats.hh index 12edc293a..e949c5950 100644 --- a/include/ignition/math/SignalStats.hh +++ b/include/ignition/math/SignalStats.hh @@ -18,10 +18,10 @@ #define IGNITION_MATH_SIGNALSTATS_HH_ #include -#include #include #include #include +#include namespace ignition { @@ -29,10 +29,6 @@ namespace ignition { // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - /// \brief Forward declare private data class. - class SignalStatisticPrivate; - /// \class SignalStatistic SignalStats.hh ignition/math/SignalStats.hh /// \brief Statistical properties of a discrete time scalar signal. class IGNITION_MATH_VISIBLE SignalStatistic @@ -40,13 +36,6 @@ namespace ignition /// \brief Constructor public: SignalStatistic(); - /// \brief Destructor - public: virtual ~SignalStatistic(); - - /// \brief Copy constructor - /// \param[in] _ss SignalStatistic to copy - public: SignalStatistic(const SignalStatistic &_ss); - /// \brief Get the current value of the statistical measure. /// \return Current value of the statistical measure. public: virtual double Value() const = 0; @@ -66,17 +55,13 @@ namespace ignition /// \brief Forget all previous data. public: virtual void Reset(); -#ifdef _WIN32 -// Disable warning C4251 which is triggered by -// std::unique_ptr -#pragma warning(push) -#pragma warning(disable: 4251) -#endif + public: class Implementation; + IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING /// \brief Pointer to private data. - protected: std::unique_ptr dataPtr; -#ifdef _WIN32 -#pragma warning(pop) -#endif + /// Not using macros as it needs to be protected to be accessed from + /// derived classes + protected: ::ignition::utils::ImplPtr dataPtr; + IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; /// \} @@ -181,8 +166,6 @@ namespace ignition }; /// \} - /// \brief Forward declare private data class. - class SignalStatsPrivate; /// \class SignalStats SignalStats.hh ignition/math/SignalStats.hh /// \brief Collection of statistics for a scalar signal. @@ -191,13 +174,6 @@ namespace ignition /// \brief Constructor public: SignalStats(); - /// \brief Destructor - public: ~SignalStats(); - - /// \brief Copy constructor - /// \param[in] _ss SignalStats to copy - public: SignalStats(const SignalStats &_ss); - /// \brief Get number of data points in first statistic. /// Technically you can have different numbers of data points /// in each statistic if you call InsertStatistic after InsertData, @@ -238,22 +214,8 @@ namespace ignition /// \brief Forget all previous data. public: void Reset(); - /// \brief Assignment operator - /// \param[in] _s A SignalStats to copy - /// \return this - public: SignalStats &operator=(const SignalStats &_s); - -#ifdef _WIN32 -// Disable warning C4251 which is triggered by -// std::unique_ptr -#pragma warning(push) -#pragma warning(disable: 4251) -#endif /// \brief Pointer to private data. - private: std::unique_ptr dataPtr; -#ifdef _WIN32 -#pragma warning(pop) -#endif + IGN_UTILS_IMPL_PTR(dataPtr) }; } /// \} diff --git a/include/ignition/math/Sphere.hh b/include/ignition/math/Sphere.hh index d9bfe89aa..605324df1 100644 --- a/include/ignition/math/Sphere.hh +++ b/include/ignition/math/Sphere.hh @@ -52,9 +52,6 @@ namespace ignition /// \param[in] _mat Material property for the sphere. public: Sphere(const Precision _radius, const Material &_mat); - /// \brief Destructor - public: ~Sphere() = default; - /// \brief Get the radius in meters. /// \return The radius of the sphere in meters. public: Precision Radius() const; diff --git a/include/ignition/math/SphericalCoordinates.hh b/include/ignition/math/SphericalCoordinates.hh index d096e8567..1e03aeb8d 100644 --- a/include/ignition/math/SphericalCoordinates.hh +++ b/include/ignition/math/SphericalCoordinates.hh @@ -17,13 +17,13 @@ #ifndef IGNITION_MATH_SPHERICALCOORDINATES_HH_ #define IGNITION_MATH_SPHERICALCOORDINATES_HH_ -#include #include #include #include #include #include +#include namespace ignition { @@ -31,8 +31,6 @@ namespace ignition { // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - class SphericalCoordinatesPrivate; /// \class SphericalCoordinates SphericalCoordinates.hh commmon/common.hh /// \brief Convert spherical coordinates for planetary surfaces. @@ -83,12 +81,6 @@ namespace ignition const double _elevation, const ignition::math::Angle &_heading); - /// \brief Copy constructor. - /// \param[in] _sc Spherical coordinates to copy. - public: SphericalCoordinates(const SphericalCoordinates &_sc); - - /// \brief Destructor. - public: ~SphericalCoordinates(); /// \brief Convert a Cartesian position vector to geodetic coordinates. /// \param[in] _xyz Cartesian position vector in the world frame. @@ -210,25 +202,8 @@ namespace ignition /// \return true if this != _sc public: bool operator!=(const SphericalCoordinates &_sc) const; - /// \brief Assignment operator - /// \param[in] _sc The spherical coordinates to copy from. - /// \return this - public: SphericalCoordinates &operator=( - const SphericalCoordinates &_sc); - - -#ifdef _WIN32 -// Disable warning C4251 which is triggered by -// std::unique_ptr -#pragma warning(push) -#pragma warning(disable: 4251) -#endif - /// \internal /// \brief Pointer to the private data - private: std::unique_ptr dataPtr; -#ifdef _WIN32 -#pragma warning(pop) -#endif + IGN_UTILS_IMPL_PTR(dataPtr) }; /// \} } diff --git a/include/ignition/math/Spline.hh b/include/ignition/math/Spline.hh index 2fc3703f9..f2a4997e8 100644 --- a/include/ignition/math/Spline.hh +++ b/include/ignition/math/Spline.hh @@ -22,6 +22,7 @@ #include #include #include +#include namespace ignition { @@ -32,7 +33,6 @@ namespace ignition // // Forward declare private classes class ControlPoint; - class SplinePrivate; /// \class Spline Spline.hh ignition/math/Spline.hh /// \brief Splines @@ -41,9 +41,6 @@ namespace ignition /// \brief constructor public: Spline(); - /// \brief destructor - public: ~Spline(); - /// \brief Sets the tension parameter. /// \remarks A value of 0 results in a Catmull-Rom /// spline. @@ -258,7 +255,7 @@ namespace ignition /// \internal /// \brief Private data pointer - private: SplinePrivate *dataPtr; + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/Stopwatch.hh b/include/ignition/math/Stopwatch.hh index 2e302d2fc..f9a12a62e 100644 --- a/include/ignition/math/Stopwatch.hh +++ b/include/ignition/math/Stopwatch.hh @@ -19,9 +19,9 @@ #define IGNITION_MATH_STOPWATCH_HH_ #include -#include #include #include +#include namespace ignition { @@ -32,11 +32,6 @@ namespace ignition // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - // Forward declarations. - class StopwatchPrivate; - - // /// \class Stopwatch Stopwatch.hh ignition/math/Stopwatch.hh /// \brief The Stopwatch keeps track of time spent in the run state, /// accessed through ElapsedRunTime(), and time spent in the stop state, @@ -63,17 +58,6 @@ namespace ignition /// \brief Constructor. public: Stopwatch(); - /// \brief Copy constructor - /// \param[in] _watch The stop watch to copy. - public: Stopwatch(const Stopwatch &_watch); - - /// \brief Move constructor - /// \param[in] _watch The stop watch to move. - public: Stopwatch(Stopwatch &&_watch) noexcept; - - /// \brief Destructor. - public: ~Stopwatch(); - /// \brief Start the stopwatch. /// \param[in] _reset If true the stopwatch is reset first. /// \return True if the the stopwatch was started. This will return @@ -129,27 +113,8 @@ namespace ignition /// \return True if this watch does not equal the provided watch. public: bool operator!=(const Stopwatch &_watch) const; - /// \brief Copy assignment operator - /// \param[in] _watch The stop watch to copy. - /// \return Reference to this. - public: Stopwatch &operator=(const Stopwatch &_watch); - - /// \brief Move assignment operator - /// \param[in] _watch The stop watch to move. - /// \return Reference to this. - public: Stopwatch &operator=(Stopwatch &&_watch); - -#ifdef _WIN32 -// Disable warning C4251 which is triggered by -// std::unique_ptr -#pragma warning(push) -#pragma warning(disable: 4251) -#endif /// \brief Private data pointer. - private: std::unique_ptr dataPtr; -#ifdef _WIN32 -#pragma warning(pop) -#endif + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/Temperature.hh b/include/ignition/math/Temperature.hh index 2df669095..1c8063ac4 100644 --- a/include/ignition/math/Temperature.hh +++ b/include/ignition/math/Temperature.hh @@ -18,11 +18,12 @@ #define IGNITION_MATH_TEMPERATURE_HH_ #include -#include #include #include #include "ignition/math/Helpers.hh" +#include + namespace ignition { @@ -30,10 +31,6 @@ namespace ignition { // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - // Forward declare private data class. - class TemperaturePrivate; - /// \brief A class that stores temperature information, and allows /// conversion between different units. /// @@ -81,23 +78,12 @@ namespace ignition /// \brief Default constructor. public: Temperature(); - /// \brief Default destructor. - public: ~Temperature(); - /// \brief Kelvin value constructor. This is a conversion constructor, /// and assumes the passed in value is in Kelvin. /// \param[in] _temp Temperature in Kelvin. // cppcheck-suppress noExplicitConstructor public: Temperature(double _temp); - /// \brief Copy constructor. - /// \param[in] _temp Temperature object to copy. - public: Temperature(const Temperature &_temp); - - /// \brief Move constructor. - /// \param[in] _temp Temperature object to move. - public: Temperature(Temperature &&_temp); - /// \brief Convert Kelvin to Celsius. /// \param[in] _temp Temperature in Kelvin. /// \return Temperature in Celsius. @@ -162,16 +148,6 @@ namespace ignition /// \return Reference to this instance. public: Temperature &operator=(double _temp); - /// \brief Assignment operator. - /// \param[in] _temp Temperature object. - /// \return Reference to this instance. - public: Temperature &operator=(const Temperature &_temp); - - /// \brief Move operator. - /// \param[in] _temp Temperature object to move. - /// \return Reference to this instance. - public: Temperature &operator=(Temperature &&_temp); - /// \brief Addition operator. /// \param[in] _temp Temperature in Kelvin. /// \return Resulting temperature. @@ -386,17 +362,7 @@ namespace ignition return _in; } -#ifdef _WIN32 -// Disable warning C4251 which is triggered by -// std::unique_ptr -#pragma warning(push) -#pragma warning(disable: 4251) -#endif - /// \brief Private data pointer. - private: std::unique_ptr dataPtr; -#ifdef _WIN32 -#pragma warning(pop) -#endif + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/Vector3Stats.hh b/include/ignition/math/Vector3Stats.hh index 65d45ba45..1e85305e8 100644 --- a/include/ignition/math/Vector3Stats.hh +++ b/include/ignition/math/Vector3Stats.hh @@ -22,6 +22,7 @@ #include #include #include +#include namespace ignition { @@ -29,10 +30,6 @@ namespace ignition { // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { - // - /// \brief Forward declare private data class. - class Vector3StatsPrivate; - /// \class Vector3Stats Vector3Stats.hh ignition/math/Vector3Stats.hh /// \brief Collection of statistics for a Vector3 signal. class IGNITION_MATH_VISIBLE Vector3Stats @@ -40,9 +37,6 @@ namespace ignition /// \brief Constructor public: Vector3Stats(); - /// \brief Destructor - public: ~Vector3Stats(); - /// \brief Add a new sample to the statistical measures. /// \param[in] _data New signal data point. public: void InsertData(const Vector3d &_data); @@ -103,7 +97,7 @@ namespace ignition public: SignalStats &Mag(); /// \brief Pointer to private data. - protected: Vector3StatsPrivate *dataPtr; + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/src/AxisAlignedBox.cc b/src/AxisAlignedBox.cc index f917633bd..61d735401 100644 --- a/src/AxisAlignedBox.cc +++ b/src/AxisAlignedBox.cc @@ -21,7 +21,7 @@ using namespace ignition; using namespace math; // Private data for AxisAlignedBox class -class ignition::math::AxisAlignedBoxPrivate +class ignition::math::AxisAlignedBox::Implementation { /// \brief Minimum corner of the box public: Vector3d min = Vector3d(MAX_D, MAX_D, MAX_D); @@ -32,14 +32,14 @@ class ignition::math::AxisAlignedBoxPrivate ////////////////////////////////////////////////// AxisAlignedBox::AxisAlignedBox() -: dataPtr(new AxisAlignedBoxPrivate) +: dataPtr(ignition::utils::MakeImpl()) { } ////////////////////////////////////////////////// AxisAlignedBox::AxisAlignedBox(double _vec1X, double _vec1Y, double _vec1Z, double _vec2X, double _vec2Y, double _vec2Z) -: dataPtr(new AxisAlignedBoxPrivate) +: AxisAlignedBox() { this->dataPtr->min.Set(_vec1X, _vec1Y, _vec1Z); this->dataPtr->max.Set(_vec2X, _vec2Y, _vec2Z); @@ -50,7 +50,7 @@ AxisAlignedBox::AxisAlignedBox(double _vec1X, double _vec1Y, double _vec1Z, ////////////////////////////////////////////////// AxisAlignedBox::AxisAlignedBox(const Vector3d &_vec1, const Vector3d &_vec2) -: dataPtr(new AxisAlignedBoxPrivate) +: AxisAlignedBox() { this->dataPtr->min = _vec1; this->dataPtr->min.Min(_vec2); @@ -59,21 +59,6 @@ AxisAlignedBox::AxisAlignedBox(const Vector3d &_vec1, const Vector3d &_vec2) this->dataPtr->max.Max(_vec1); } -////////////////////////////////////////////////// -AxisAlignedBox::AxisAlignedBox(const AxisAlignedBox &_b) -: dataPtr(new AxisAlignedBoxPrivate) -{ - this->dataPtr->min = _b.dataPtr->min; - this->dataPtr->max = _b.dataPtr->max; -} - -////////////////////////////////////////////////// -AxisAlignedBox::~AxisAlignedBox() -{ - delete this->dataPtr; - this->dataPtr = NULL; -} - ////////////////////////////////////////////////// double AxisAlignedBox::XLength() const { @@ -106,7 +91,6 @@ math::Vector3d AxisAlignedBox::Center() const return 0.5 * this->dataPtr->min + 0.5 * this->dataPtr->max; } - ////////////////////////////////////////////////// void AxisAlignedBox::Merge(const AxisAlignedBox &_box) { @@ -114,15 +98,6 @@ void AxisAlignedBox::Merge(const AxisAlignedBox &_box) this->dataPtr->max.Max(_box.dataPtr->max); } -////////////////////////////////////////////////// -AxisAlignedBox &AxisAlignedBox::operator =(const AxisAlignedBox &_b) -{ - this->dataPtr->max = _b.dataPtr->max; - this->dataPtr->min = _b.dataPtr->min; - - return *this; -} - ////////////////////////////////////////////////// AxisAlignedBox AxisAlignedBox::operator+(const AxisAlignedBox &_b) const { diff --git a/src/Box_TEST.cc b/src/Box_TEST.cc index c15452f7c..8c9f7dcd2 100644 --- a/src/Box_TEST.cc +++ b/src/Box_TEST.cc @@ -77,6 +77,24 @@ TEST(BoxTest, Constructor) math::Material(math::MaterialType::WOOD)); EXPECT_EQ(box, box2); } + + // Copy Constructor + { + math::Boxd box(math::Vector3d(2.2, 2.0, 10.0), + math::Material(math::MaterialType::WOOD)); + math::Boxd box2(box); + EXPECT_EQ(math::Vector3d(2.2, 2.0, 10.0), box2.Size()); + EXPECT_EQ(math::Material(math::MaterialType::WOOD), box2.Material()); + } + + // Move Constructor + { + math::Boxd box(math::Vector3d(2.2, 2.0, 10.0), + math::Material(math::MaterialType::WOOD)); + math::Boxd box2(std::move(box)); + EXPECT_EQ(math::Vector3d(2.2, 2.0, 10.0), box2.Size()); + EXPECT_EQ(math::Material(math::MaterialType::WOOD), box2.Material()); + } } ////////////////////////////////////////////////// diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index e39a51f0e..f3bd16960 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -6,74 +6,14 @@ ign_get_libsources_and_unittests(sources gtest_sources) # Create the library target ign_create_core_library(SOURCES ${sources} CXX_STANDARD ${c++standard}) +target_link_libraries(${PROJECT_LIBRARY_TARGET_NAME} + PUBLIC + ignition-utils${IGN_UTILS_VER}::ignition-utils${IGN_UTILS_VER} +) + # Build the unit tests ign_build_tests(TYPE UNIT SOURCES ${gtest_sources}) # graph namespace add_subdirectory(graph) -################################################# -# Setup swig -if (SWIG_FOUND) - include(${SWIG_USE_FILE}) - set(CMAKE_SWIG_FLAGS "") - - include_directories(${PROJECT_SOURCE_DIR}/include) - - set(swig_files - ruby - Angle - GaussMarkovProcess - Helpers - Matrix3 - Pose3 - Quaternion - Rand - Temperature - Vector2 - Vector3 - Vector4) -endif() - -################################################# -# Create and install Ruby interfaces -# Example usage -# $ export RUBYLIB=/usr/local/lib/ruby -# $ ruby -e "require 'ignition/math'; a = Ignition::Math::Angle.new(20); puts a.Degree()" -if (RUBY_FOUND) - include_directories(${RUBY_INCLUDE_DIRS}) - - foreach (swig_file ${swig_files}) - # Assuming that each swig file has a test - list(APPEND ruby_tests ${swig_file}_TEST) - - # Generate the list if .i files - list(APPEND swig_i_files ${swig_file}.i) - - # Removing warning from auto-generated files. - set_source_files_properties(${swig_file}RUBY_wrap.cxx - PROPERTIES COMPILE_FLAGS "-w") - endforeach() - - # Turn on c++ - set_source_files_properties(${swig_i_files} PROPERTIES CPLUSPLUS ON) - - # Create the ruby library - - if(CMAKE_VERSION VERSION_GREATER 3.8.0) - SWIG_ADD_LIBRARY(math LANGUAGE ruby SOURCES ruby.i ${swig_i_files} ${sources}) - else() - SWIG_ADD_MODULE(math ruby ruby.i ${swig_i_files} ${sources}) - endif() - - SWIG_LINK_LIBRARIES(math ${RUBY_LIBRARY}) - target_compile_features(math PUBLIC ${IGN_CXX_${c++standard}_FEATURES}) - install(TARGETS math DESTINATION ${IGN_LIB_INSTALL_DIR}/ruby/ignition) - - # Add the ruby tests - foreach (test ${ruby_tests}) - add_test(NAME ${test}.rb COMMAND - ruby -I${CMAKE_BINARY_DIR}/lib ${CMAKE_SOURCE_DIR}/src/${test}.rb - --gtest_output=xml:${CMAKE_BINARY_DIR}/test_results/${test}rb.xml) - endforeach() -endif() diff --git a/src/DiffDriveOdometry.cc b/src/DiffDriveOdometry.cc index d184b8e02..fd0096d7f 100644 --- a/src/DiffDriveOdometry.cc +++ b/src/DiffDriveOdometry.cc @@ -23,7 +23,7 @@ using namespace math; // The implementation was borrowed from: https://github.com/ros-controls/ros_controllers/blob/melodic-devel/diff_drive_controller/src/odometry.cpp -class ignition::math::DiffDriveOdometryPrivate +class ignition::math::DiffDriveOdometry::Implementation { /// \brief Integrates the velocities (linear and angular) using 2nd order /// Runge-Kutta. @@ -82,17 +82,12 @@ class ignition::math::DiffDriveOdometryPrivate ////////////////////////////////////////////////// DiffDriveOdometry::DiffDriveOdometry(size_t _windowSize) - : dataPtr(new DiffDriveOdometryPrivate) + : dataPtr(ignition::utils::MakeImpl()) { this->dataPtr->linearMean.SetWindowSize(_windowSize); this->dataPtr->angularMean.SetWindowSize(_windowSize); } -////////////////////////////////////////////////// -DiffDriveOdometry::~DiffDriveOdometry() -{ -} - ////////////////////////////////////////////////// void DiffDriveOdometry::Init(const clock::time_point &_time) { @@ -211,7 +206,7 @@ const Angle &DiffDriveOdometry::AngularVelocity() const } ////////////////////////////////////////////////// -void DiffDriveOdometryPrivate::IntegrateRungeKutta2( +void DiffDriveOdometry::Implementation::IntegrateRungeKutta2( double _linear, double _angular) { const double direction = *this->heading + _angular * 0.5; @@ -223,7 +218,8 @@ void DiffDriveOdometryPrivate::IntegrateRungeKutta2( } ////////////////////////////////////////////////// -void DiffDriveOdometryPrivate::IntegrateExact(double _linear, double _angular) +void DiffDriveOdometry::Implementation::IntegrateExact( + double _linear, double _angular) { if (std::fabs(_angular) < 1e-6) { diff --git a/src/Frustum.cc b/src/Frustum.cc index 44a328665..937b901b1 100644 --- a/src/Frustum.cc +++ b/src/Frustum.cc @@ -19,14 +19,53 @@ #include "ignition/math/AxisAlignedBox.hh" #include "ignition/math/Frustum.hh" #include "ignition/math/Matrix4.hh" -#include "FrustumPrivate.hh" using namespace ignition; using namespace math; +/// \internal +/// \brief Private data for the Frustum class +class Frustum::Implementation +{ + /// \param[in] _pose Pose of the frustum, which is the vertex (top of + /// the pyramid). + + /// \brief Near distance + /// This is the distance from the frustum's vertex to the closest plane + public: double near {0}; + + /// \brief Far distance + /// This is the distance from the frustum's vertex to the farthest plane. + public: double far {1}; + + /// \brief Field of view + /// The field of view is the angle between the frustum's vertex and the + /// edges of the near or far plane. + /// This value represents the horizontal angle. + public: math::Angle fov {IGN_DTOR(45)}; + + /// \brief Aspect ratio of the near and far planes. This is the + // width divided by the height. + public: double aspectRatio {1}; + + /// \brief Pose of the frustum + /// Pose of the frustum, which is the vertex (top of the pyramid). + public: math::Pose3d pose {Pose3d::Zero}; + + /// \brief Each plane of the frustum. + /// \sa Frustum::FrustumPlane + public: std::array planes; + + /// \brief Each corner of the frustum. + public: std::array points; + + /// \brief each edge of the frustum. + public: std::array, 12> edges; +}; + ///////////////////////////////////////////////// Frustum::Frustum() - : dataPtr(new FrustumPrivate(0, 1, IGN_DTOR(45), 1, Pose3d::Zero)) + : dataPtr(ignition::utils::MakeImpl()) { } @@ -36,29 +75,20 @@ Frustum::Frustum(const double _near, const Angle &_fov, const double _aspectRatio, const Pose3d &_pose) - : dataPtr(new FrustumPrivate(_near, _far, _fov, _aspectRatio, _pose)) + : Frustum() { + + this->dataPtr->near = _near; + this->dataPtr->far = _far; + this->dataPtr->fov = _fov; + this->dataPtr->aspectRatio = _aspectRatio; + this->dataPtr->pose = _pose; + // Compute plane based on near distance, far distance, field of view, // aspect ratio, and pose this->ComputePlanes(); } -///////////////////////////////////////////////// -Frustum::~Frustum() -{ - delete this->dataPtr; - this->dataPtr = NULL; -} - -///////////////////////////////////////////////// -Frustum::Frustum(const Frustum &_p) - : dataPtr(new FrustumPrivate(_p.Near(), _p.Far(), _p.FOV(), - _p.AspectRatio(), _p.Pose())) -{ - for (int i = 0; i < 6; ++i) - this->dataPtr->planes[i] = _p.dataPtr->planes[i]; -} - ///////////////////////////////////////////////// Planed Frustum::Plane(const FrustumPlane _plane) const { @@ -335,16 +365,3 @@ void Frustum::ComputePlanes() norm = Vector3d::Normal(nearBottomLeft, nearBottomRight, farBottomRight); this->dataPtr->planes[FRUSTUM_PLANE_BOTTOM].Set(norm, bottomCenter.Dot(norm)); } - -////////////////////////////////////////////////// -Frustum &Frustum::operator =(const Frustum &_f) -{ - this->dataPtr->near = _f.dataPtr->near; - this->dataPtr->far = _f.dataPtr->far; - this->dataPtr->fov = _f.dataPtr->fov; - this->dataPtr->aspectRatio = _f.dataPtr->aspectRatio; - this->dataPtr->pose = _f.dataPtr->pose; - this->ComputePlanes(); - - return *this; -} diff --git a/src/FrustumPrivate.hh b/src/FrustumPrivate.hh deleted file mode 100644 index 3077655e5..000000000 --- a/src/FrustumPrivate.hh +++ /dev/null @@ -1,88 +0,0 @@ -/* - * Copyright (C) 2015 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * -*/ -#ifndef IGNITION_MATH_FRUSTUMPRIVATE_HH_ -#define IGNITION_MATH_FRUSTUMPRIVATE_HH_ - -#include -#include -#include -#include -#include -#include - -namespace ignition -{ - namespace math - { - inline namespace IGNITION_MATH_VERSION_NAMESPACE - { - /// \internal - /// \brief Private data for the Frustum class - class FrustumPrivate - { - /// \brief Constructor - /// \param[in] _near Near distance. This is the distance from - /// the frustum's vertex to the closest plane - /// \param[in] _far Far distance. This is the distance from the - /// frustum's vertex to the farthest plane. - /// \param[in] _fov Field of view. The field of view is the - /// angle between the frustum's vertex and the edges of the near or far - /// plane. This value represents the horizontal angle. - /// \param[in] _aspectRatio The aspect ratio, which is the width divided - /// by height of the near or far planes. - /// \param[in] _pose Pose of the frustum, which is the vertex (top of - /// the pyramid). - public: FrustumPrivate(const double _near, - const double _far, - const math::Angle &_fov, - const double _aspectRatio, - const Pose3d &_pose) - : near(_near), far(_far), fov(_fov), - aspectRatio(_aspectRatio), pose(_pose) - { - } - - /// \brief Near distance - public: double near; - - /// \brief Far distance - public: double far; - - /// \brief Field of view - public: math::Angle fov; - - /// \brief Aspect ratio of the near and far planes. This is the - // width divided by the height. - public: double aspectRatio; - - /// \brief Pose of the frustum - public: math::Pose3d pose; - - /// \brief Each plane of the frustum. - /// \sa Frustum::FrustumPlane - public: std::array planes; - - /// \brief Each corner of the frustum. - public: std::array points; - - /// \brief each edge of the frustum. - public: std::array, 12> edges; - }; - } - } -} -#endif diff --git a/src/GaussMarkovProcess.cc b/src/GaussMarkovProcess.cc index 311de7e54..694c30123 100644 --- a/src/GaussMarkovProcess.cc +++ b/src/GaussMarkovProcess.cc @@ -21,7 +21,7 @@ using namespace ignition::math; ////////////////////////////////////////////////// -class ignition::math::GaussMarkovProcessPrivate +class ignition::math::GaussMarkovProcess::Implementation { /// \brief Current process value. public: double value{0}; @@ -41,23 +41,18 @@ class ignition::math::GaussMarkovProcessPrivate ////////////////////////////////////////////////// GaussMarkovProcess::GaussMarkovProcess() - : dataPtr(new GaussMarkovProcessPrivate) + : dataPtr(ignition::utils::MakeImpl()) { } ////////////////////////////////////////////////// GaussMarkovProcess::GaussMarkovProcess(double _start, double _theta, double _mu, double _sigma) - : dataPtr(new GaussMarkovProcessPrivate) + : GaussMarkovProcess() { this->Set(_start, _theta, _mu, _sigma); } -////////////////////////////////////////////////// -GaussMarkovProcess::~GaussMarkovProcess() -{ -} - ////////////////////////////////////////////////// void GaussMarkovProcess::Set(double _start, double _theta, double _mu, double _sigma) diff --git a/src/Kmeans.cc b/src/Kmeans.cc index 41dce68c1..99cb73ec8 100644 --- a/src/Kmeans.cc +++ b/src/Kmeans.cc @@ -27,18 +27,11 @@ using namespace math; ////////////////////////////////////////////////// Kmeans::Kmeans(const std::vector &_obs) -: dataPtr(new KmeansPrivate) +: dataPtr(ignition::utils::MakeImpl()) { this->Observations(_obs); } -////////////////////////////////////////////////// -Kmeans::~Kmeans() -{ - delete this->dataPtr; - this->dataPtr = NULL; -} - ////////////////////////////////////////////////// std::vector Kmeans::Observations() const { diff --git a/src/KmeansPrivate.hh b/src/KmeansPrivate.hh index bcda8ef77..d0008dac5 100644 --- a/src/KmeansPrivate.hh +++ b/src/KmeansPrivate.hh @@ -30,7 +30,7 @@ namespace ignition { /// \internal /// \brief Private data for Kmeans class - class KmeansPrivate + class Kmeans::Implementation { /// \brief Observations. public: std::vector obs; diff --git a/src/Material.cc b/src/Material.cc index 0c6647fa2..52b622a8b 100644 --- a/src/Material.cc +++ b/src/Material.cc @@ -29,7 +29,7 @@ using namespace ignition; using namespace math; // Private data for the Material class -class ignition::math::MaterialPrivate +class ignition::math::Material::Implementation { /// \brief Set from a kMaterialData constant. public: void SetFrom(const std::pair& _input) @@ -52,13 +52,13 @@ class ignition::math::MaterialPrivate /////////////////////////////// Material::Material() -: dataPtr(new MaterialPrivate) +: dataPtr(ignition::utils::MakeImpl()) { } /////////////////////////////// Material::Material(const MaterialType _type) -: dataPtr(new MaterialPrivate) +: Material() { auto iter = std::find_if(std::begin(kMaterialData), std::end(kMaterialData), [_type](const auto& item) { @@ -72,7 +72,7 @@ Material::Material(const MaterialType _type) /////////////////////////////// Material::Material(const std::string &_typename) -: dataPtr(new MaterialPrivate) +: Material() { // Convert to lowercase. std::string material = _typename; @@ -90,34 +90,11 @@ Material::Material(const std::string &_typename) /////////////////////////////// Material::Material(const double _density) -: dataPtr(new MaterialPrivate) +: Material() { this->dataPtr->density = _density; } -/////////////////////////////// -Material::Material(const Material &_material) -: dataPtr(new MaterialPrivate) -{ - this->dataPtr->name = _material.Name(); - this->dataPtr->density = _material.Density(); - this->dataPtr->type = _material.Type(); -} - -/////////////////////////////// -Material::Material(Material &&_material) -{ - this->dataPtr = _material.dataPtr; - _material.dataPtr = new MaterialPrivate; -} - -/////////////////////////////// -Material::~Material() -{ - delete this->dataPtr; - this->dataPtr = nullptr; -} - /////////////////////////////// const std::map &Material::Predefined() { @@ -155,24 +132,6 @@ bool Material::operator!=(const Material &_material) const return !(*this == _material); } -/////////////////////////////// -Material &Material::operator=(const Material &_material) -{ - this->dataPtr->name = _material.Name(); - this->dataPtr->density = _material.Density(); - this->dataPtr->type = _material.Type(); - return *this; -} - -/////////////////////////////// -Material &Material::operator=(Material &&_material) -{ - delete this->dataPtr; - this->dataPtr = _material.dataPtr; - _material.dataPtr = new MaterialPrivate; - return *this; -} - /////////////////////////////// MaterialType Material::Type() const { diff --git a/src/Material_TEST.cc b/src/Material_TEST.cc index 1d79fc820..72e3c682d 100644 --- a/src/Material_TEST.cc +++ b/src/Material_TEST.cc @@ -101,13 +101,11 @@ TEST(MaterialTest, Accessors) Material mat4(std::move(mat3)); EXPECT_EQ(mat2, mat4); Material defaultMat; - EXPECT_EQ(defaultMat, mat3); // Test move operator Material mat5; mat5 = std::move(mat4); EXPECT_EQ(mat2, mat5); - EXPECT_EQ(defaultMat, mat4); } { diff --git a/src/RollingMean.cc b/src/RollingMean.cc index 3510d0619..067e2bb4d 100644 --- a/src/RollingMean.cc +++ b/src/RollingMean.cc @@ -23,7 +23,7 @@ using namespace ignition::math; /// \brief Private data -class ignition::math::RollingMeanPrivate +class ignition::math::RollingMean::Implementation { /// \brief The window size public: size_t windowSize{10}; @@ -34,17 +34,12 @@ class ignition::math::RollingMeanPrivate ////////////////////////////////////////////////// RollingMean::RollingMean(size_t _windowSize) - : dataPtr(new RollingMeanPrivate) + : dataPtr(ignition::utils::MakeImpl()) { if (_windowSize > 0) this->dataPtr->windowSize = _windowSize; } -////////////////////////////////////////////////// -RollingMean::~RollingMean() -{ -} - ////////////////////////////////////////////////// double RollingMean::Mean() const { diff --git a/src/RotationSpline.cc b/src/RotationSpline.cc index 974fbc311..e8c743e4a 100644 --- a/src/RotationSpline.cc +++ b/src/RotationSpline.cc @@ -16,22 +16,29 @@ */ #include "ignition/math/Quaternion.hh" #include "ignition/math/RotationSpline.hh" -#include "RotationSplinePrivate.hh" using namespace ignition; using namespace math; -///////////////////////////////////////////////// -RotationSpline::RotationSpline() -: dataPtr(new RotationSplinePrivate) +/// \internal +/// \brief Private data for RotationSpline +class RotationSpline::Implementation { -} + /// \brief Automatic recalculation of tangents when control points are + /// updated + public: bool autoCalc = {true}; + + /// \brief the control points + public: std::vector points; + + /// \brief the tangents + public: std::vector tangents; +}; ///////////////////////////////////////////////// -RotationSpline::~RotationSpline() +RotationSpline::RotationSpline() +: dataPtr(ignition::utils::MakeImpl()) { - delete this->dataPtr; - this->dataPtr = NULL; } ///////////////////////////////////////////////// diff --git a/src/RotationSplinePrivate.cc b/src/RotationSplinePrivate.cc deleted file mode 100644 index 1396e829e..000000000 --- a/src/RotationSplinePrivate.cc +++ /dev/null @@ -1,26 +0,0 @@ -/* - * Copyright (C) 2015 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * -*/ -#include "RotationSplinePrivate.hh" - -using namespace ignition; -using namespace math; - -///////////////////////////////////////////////// -RotationSplinePrivate::RotationSplinePrivate() -: autoCalc(true) -{ -} diff --git a/src/RotationSplinePrivate.hh b/src/RotationSplinePrivate.hh deleted file mode 100644 index 34af9b9f1..000000000 --- a/src/RotationSplinePrivate.hh +++ /dev/null @@ -1,50 +0,0 @@ -/* - * Copyright (C) 2015 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * -*/ -#ifndef IGNITION_MATH_ROTATIONSPLINEPRIVATE_HH_ -#define IGNITION_MATH_ROTATIONSPLINEPRIVATE_HH_ - -#include -#include -#include "ignition/math/Quaternion.hh" - -namespace ignition -{ - namespace math - { - inline namespace IGNITION_MATH_VERSION_NAMESPACE - { - /// \internal - /// \brief Private data for RotationSpline - class RotationSplinePrivate - { - /// \brief Constructor - public: RotationSplinePrivate(); - - /// \brief Automatic recalculation of tangents when control points are - /// updated - public: bool autoCalc; - - /// \brief the control points - public: std::vector points; - - /// \brief the tangents - public: std::vector tangents; - }; - } - } -} -#endif diff --git a/src/SemanticVersion.cc b/src/SemanticVersion.cc index ca594d588..6ede46ee6 100644 --- a/src/SemanticVersion.cc +++ b/src/SemanticVersion.cc @@ -28,7 +28,7 @@ namespace ignition { inline namespace IGNITION_MATH_VERSION_NAMESPACE { - class SemanticVersionPrivate + class SemanticVersion::Implementation { /// \brief Major revision (incompatible api changes) public: unsigned int maj = 0; @@ -55,13 +55,13 @@ namespace ignition ///////////////////////////////////////////////// SemanticVersion::SemanticVersion() -: dataPtr(new SemanticVersionPrivate()) +: dataPtr(ignition::utils::MakeImpl()) { } ///////////////////////////////////////////////// SemanticVersion::SemanticVersion(const std::string &_versionStr) -: dataPtr(new SemanticVersionPrivate()) +: SemanticVersion() { this->Parse(_versionStr); } @@ -72,7 +72,7 @@ SemanticVersion::SemanticVersion(const unsigned int _major, const unsigned int _patch, const std::string &_prerelease, const std::string &_build) -: dataPtr(new SemanticVersionPrivate()) +: SemanticVersion() { this->dataPtr->maj = _major; this->dataPtr->min = _minor; @@ -81,25 +81,6 @@ SemanticVersion::SemanticVersion(const unsigned int _major, this->dataPtr->build = _build; } -///////////////////////////////////////////////// -SemanticVersion::SemanticVersion(const SemanticVersion &_copy) -: dataPtr(new SemanticVersionPrivate()) -{ - *this->dataPtr = *_copy.dataPtr; -} - -///////////////////////////////////////////////// -SemanticVersion& SemanticVersion::operator=(const SemanticVersion &_other) -{ - *this->dataPtr = *_other.dataPtr; - return *this; -} - -///////////////////////////////////////////////// -SemanticVersion::~SemanticVersion() -{ -} - ///////////////////////////////////////////////// std::string SemanticVersion::Version() const { diff --git a/src/SignalStats.cc b/src/SignalStats.cc index 4523bef3a..7d43254fc 100644 --- a/src/SignalStats.cc +++ b/src/SignalStats.cc @@ -24,24 +24,13 @@ using namespace math; ////////////////////////////////////////////////// SignalStatistic::SignalStatistic() - : dataPtr(new SignalStatisticPrivate) + : dataPtr(ignition::utils::MakeImpl()) { this->dataPtr->data = 0.0; this->dataPtr->extraData = 0.0; this->dataPtr->count = 0; } -////////////////////////////////////////////////// -SignalStatistic::~SignalStatistic() -{ -} - -////////////////////////////////////////////////// -SignalStatistic::SignalStatistic(const SignalStatistic &_ss) - : dataPtr(_ss.dataPtr->Clone()) -{ -} - ////////////////////////////////////////////////// size_t SignalStatistic::Count() const { @@ -206,18 +195,7 @@ void SignalVariance::InsertData(const double _data) ////////////////////////////////////////////////// SignalStats::SignalStats() - : dataPtr(new SignalStatsPrivate) -{ -} - -////////////////////////////////////////////////// -SignalStats::~SignalStats() -{ -} - -////////////////////////////////////////////////// -SignalStats::SignalStats(const SignalStats &_ss) - : dataPtr(_ss.dataPtr->Clone()) + : dataPtr(ignition::utils::MakeImpl()) { } @@ -351,9 +329,3 @@ void SignalStats::Reset() } } -////////////////////////////////////////////////// -SignalStats &SignalStats::operator=(const SignalStats &_s) -{ - this->dataPtr = _s.dataPtr->Clone(); - return *this; -} diff --git a/src/SignalStatsPrivate.hh b/src/SignalStatsPrivate.hh index e5e045e86..2f408e7c7 100644 --- a/src/SignalStatsPrivate.hh +++ b/src/SignalStatsPrivate.hh @@ -28,7 +28,7 @@ namespace ignition inline namespace IGNITION_MATH_VERSION_NAMESPACE { /// \brief Private data class for the SignalStatistic class. - class SignalStatisticPrivate + class SignalStatistic::Implementation { /// \brief Scalar representation of signal data. public: double data; @@ -39,15 +39,6 @@ namespace ignition /// \brief Count of data values in mean. public: unsigned int count; - - /// \brief Clone the SignalStatisticPrivate object. Used for implementing - /// copy semantics. - public: std::unique_ptr Clone() const - { - std::unique_ptr dataPtr( - new SignalStatisticPrivate(*this)); - return dataPtr; - } }; class SignalStatistic; @@ -61,19 +52,10 @@ namespace ignition typedef std::vector SignalStatistic_V; /// \brief Private data class for the SignalStats class. - class SignalStatsPrivate + class SignalStats::Implementation { /// \brief Vector of `SignalStatistic`s. public: SignalStatistic_V stats; - - /// \brief Clone the SignalStatsPrivate object. Used for implementing - /// copy semantics. - public: std::unique_ptr Clone() const - { - std::unique_ptr dataPtr( - new SignalStatsPrivate(*this)); - return dataPtr; - } }; } } diff --git a/src/SphericalCoordinates.cc b/src/SphericalCoordinates.cc index e43d6e725..79f6f6e8d 100644 --- a/src/SphericalCoordinates.cc +++ b/src/SphericalCoordinates.cc @@ -39,7 +39,7 @@ const double g_EarthWGS84Flattening = 1.0/298.257223563; const double g_EarthRadius = 6371000.0; // Private data for the SphericalCoordinates class. -class ignition::math::SphericalCoordinatesPrivate +class ignition::math::SphericalCoordinates::Implementation { /// \brief Type of surface being used. public: SphericalCoordinates::SurfaceType surfaceType; @@ -102,7 +102,7 @@ SphericalCoordinates::SurfaceType SphericalCoordinates::Convert( ////////////////////////////////////////////////// SphericalCoordinates::SphericalCoordinates() - : dataPtr(new SphericalCoordinatesPrivate) + : dataPtr(ignition::utils::MakeImpl()) { this->SetSurface(EARTH_WGS84); this->SetElevationReference(0.0); @@ -110,7 +110,7 @@ SphericalCoordinates::SphericalCoordinates() ////////////////////////////////////////////////// SphericalCoordinates::SphericalCoordinates(const SurfaceType _type) - : dataPtr(new SphericalCoordinatesPrivate) + : SphericalCoordinates() { this->SetSurface(_type); this->SetElevationReference(0.0); @@ -122,7 +122,7 @@ SphericalCoordinates::SphericalCoordinates(const SurfaceType _type, const ignition::math::Angle &_longitude, const double _elevation, const ignition::math::Angle &_heading) -: dataPtr(new SphericalCoordinatesPrivate) + : SphericalCoordinates() { // Set the reference and calculate ellipse parameters this->SetSurface(_type); @@ -137,18 +137,6 @@ SphericalCoordinates::SphericalCoordinates(const SurfaceType _type, this->UpdateTransformationMatrix(); } -////////////////////////////////////////////////// -SphericalCoordinates::SphericalCoordinates(const SphericalCoordinates &_sc) - : SphericalCoordinates() -{ - (*this) = _sc; -} - -////////////////////////////////////////////////// -SphericalCoordinates::~SphericalCoordinates() -{ -} - ////////////////////////////////////////////////// SphericalCoordinates::SurfaceType SphericalCoordinates::Surface() const { @@ -542,19 +530,3 @@ bool SphericalCoordinates::operator!=(const SphericalCoordinates &_sc) const { return !(*this == _sc); } - -////////////////////////////////////////////////// -SphericalCoordinates &SphericalCoordinates::operator=( - const SphericalCoordinates &_sc) -{ - this->SetSurface(_sc.Surface()); - this->SetLatitudeReference(_sc.LatitudeReference()); - this->SetLongitudeReference(_sc.LongitudeReference()); - this->SetElevationReference(_sc.ElevationReference()); - this->SetHeadingOffset(_sc.HeadingOffset()); - - // Generate transformation matrix - this->UpdateTransformationMatrix(); - - return *this; -} diff --git a/src/Spline.cc b/src/Spline.cc index c54b3e39f..483cade93 100644 --- a/src/Spline.cc +++ b/src/Spline.cc @@ -17,29 +17,19 @@ // Note: Originally cribbed from Ogre3d. Modified to implement Cardinal // spline and catmull-rom spline -#include "SplinePrivate.hh" #include "ignition/math/Helpers.hh" #include "ignition/math/Vector4.hh" #include "ignition/math/Spline.hh" +#include "SplinePrivate.hh" + using namespace ignition; using namespace math; /////////////////////////////////////////////////////////// Spline::Spline() - : dataPtr(new SplinePrivate()) -{ - // Set up matrix - this->dataPtr->autoCalc = true; - this->dataPtr->tension = 0.0; - this->dataPtr->arcLength = INF_D; -} - -/////////////////////////////////////////////////////////// -Spline::~Spline() + : dataPtr(ignition::utils::MakeImpl()) { - delete this->dataPtr; - this->dataPtr = NULL; } /////////////////////////////////////////////////////////// diff --git a/src/SplinePrivate.cc b/src/SplinePrivate.cc index 896b5af25..168385bb7 100644 --- a/src/SplinePrivate.cc +++ b/src/SplinePrivate.cc @@ -74,15 +74,6 @@ void ComputeCubicBernsteinHermiteCoeff(const ControlPoint &_startPoint, _coeffs = bmatrix * cmatrix; } -/////////////////////////////////////////////////////////// -IntervalCubicSpline::IntervalCubicSpline() - : startPoint({Vector3d::Zero, Vector3d::Zero}), - endPoint({Vector3d::Zero, Vector3d::Zero}), - coeffs(Matrix4d::Zero), - arcLength(0.0) -{ -} - /////////////////////////////////////////////////////////// void IntervalCubicSpline::SetPoints(const ControlPoint &_startPoint, const ControlPoint &_endPoint) diff --git a/src/SplinePrivate.hh b/src/SplinePrivate.hh index ef82e2959..097cfeae8 100644 --- a/src/SplinePrivate.hh +++ b/src/SplinePrivate.hh @@ -19,9 +19,10 @@ #include #include +#include +#include #include #include -#include #include namespace ignition @@ -35,11 +36,6 @@ namespace ignition /// of arbitrary m derivatives at such point. class ControlPoint { - /// \brief Default constructor. - public: ControlPoint() - { - } - /// \brief Constructor that takes the M derivatives that /// define the control point. /// \param[in] _initList with the M derivatives. @@ -115,9 +111,6 @@ namespace ignition /// between each pair of control points. class IntervalCubicSpline { - /// \brief Dummy constructor. - public: IntervalCubicSpline(); - /// \brief Sets both control points. /// \param[in] _startPoint start control point. /// \param[in] _endPoint end control point. @@ -166,28 +159,28 @@ namespace ignition const unsigned int _mth, const double _t) const; /// \brief start control point for the curve. - private: ControlPoint startPoint; + private: ControlPoint startPoint {{Vector3d::Zero, Vector3d::Zero}}; /// \brief end control point for the curve. - private: ControlPoint endPoint; + private: ControlPoint endPoint {{Vector3d::Zero, Vector3d::Zero}}; /// \brief Bernstein-Hermite polynomial coefficients /// for interpolation. - private: Matrix4d coeffs; + private: Matrix4d coeffs {Matrix4d::Zero}; /// \brief curve arc length. - private: double arcLength; + private: double arcLength {0.0}; }; /// \brief Private data for Spline class. - class SplinePrivate + class Spline::Implementation { /// \brief when true, the tangents are recalculated when the control /// point change. - public: bool autoCalc; + public: bool autoCalc {true}; /// \brief tension of 0 = Catmull-Rom spline, otherwise a Cardinal spline. - public: double tension; + public: double tension {0.0}; /// \brief fixings for control points. public: std::vector fixings; @@ -202,7 +195,7 @@ namespace ignition public: std::vector cumulativeArcLengths; // \brief spline arc length. - public: double arcLength; + public: double arcLength {INF_D}; }; } } diff --git a/src/Stopwatch.cc b/src/Stopwatch.cc index d534125df..ebc2101d3 100644 --- a/src/Stopwatch.cc +++ b/src/Stopwatch.cc @@ -20,22 +20,8 @@ using namespace ignition::math; // Private data class -class ignition::math::StopwatchPrivate +class ignition::math::Stopwatch::Implementation { - /// \brief Default constructor. - public: StopwatchPrivate() = default; - - /// \brief Copy constructor. - /// \param[in] _watch Watch to copy. - public: explicit StopwatchPrivate(const StopwatchPrivate &_watch) - : running(_watch.running), - startTime(_watch.startTime), - stopTime(_watch.stopTime), - stopDuration(_watch.stopDuration), - runDuration(_watch.runDuration) - { - } - /// \brief True if the real time clock is running. public: bool running = false; @@ -54,24 +40,7 @@ class ignition::math::StopwatchPrivate ////////////////////////////////////////////////// Stopwatch::Stopwatch() - : dataPtr(new StopwatchPrivate) -{ -} - -////////////////////////////////////////////////// -Stopwatch::Stopwatch(const Stopwatch &_watch) - : dataPtr(new StopwatchPrivate(*_watch.dataPtr)) -{ -} - -////////////////////////////////////////////////// -Stopwatch::Stopwatch(Stopwatch &&_watch) noexcept - : dataPtr(std::move(_watch.dataPtr)) -{ -} - -////////////////////////////////////////////////// -Stopwatch::~Stopwatch() + : dataPtr(ignition::utils::MakeImpl()) { } @@ -187,17 +156,3 @@ bool Stopwatch::operator!=(const Stopwatch &_watch) const { return !(*this == _watch); } - -////////////////////////////////////////////////// -Stopwatch &Stopwatch::operator=(const Stopwatch &_watch) -{ - this->dataPtr.reset(new StopwatchPrivate(*_watch.dataPtr)); - return *this; -} - -////////////////////////////////////////////////// -Stopwatch &Stopwatch::operator=(Stopwatch &&_watch) -{ - this->dataPtr = std::move(_watch.dataPtr); - return *this; -} diff --git a/src/Temperature.cc b/src/Temperature.cc index ea23bc754..7eaff4a75 100644 --- a/src/Temperature.cc +++ b/src/Temperature.cc @@ -14,10 +14,14 @@ * limitations under the License. * */ + #include "ignition/math/Temperature.hh" +#include +#include + /// \brief Private data for the Temperature class. -class ignition::math::TemperaturePrivate +class ignition::math::Temperature::Implementation { /// \brief Temperature value in Kelvin. public: double kelvin{0.0}; @@ -28,35 +32,17 @@ using namespace math; ///////////////////////////////////////////////// Temperature::Temperature() -: dataPtr(new TemperaturePrivate) -{ -} - -///////////////////////////////////////////////// -Temperature::~Temperature() +: dataPtr(ignition::utils::MakeImpl()) { } ///////////////////////////////////////////////// Temperature::Temperature(double _temp) -: dataPtr(new TemperaturePrivate) +: Temperature() { this->dataPtr->kelvin = _temp; } -///////////////////////////////////////////////// -Temperature::Temperature(const Temperature &_temp) -: dataPtr(new TemperaturePrivate) -{ - this->dataPtr->kelvin = _temp.Kelvin(); -} - -///////////////////////////////////////////////// -Temperature::Temperature(Temperature &&_temp) -{ - this->dataPtr.reset(_temp.dataPtr.release()); -} - ///////////////////////////////////////////////// double Temperature::KelvinToCelsius(double _temp) { @@ -142,20 +128,6 @@ Temperature &Temperature::operator=(double _temp) return *this; } -///////////////////////////////////////////////// -Temperature &Temperature::operator=(const Temperature &_temp) -{ - this->SetKelvin(_temp.Kelvin()); - return *this; -} - -///////////////////////////////////////////////// -Temperature &Temperature::operator=(Temperature &&_temp) -{ - this->dataPtr.reset(_temp.dataPtr.release()); - return *this; -} - ///////////////////////////////////////////////// Temperature Temperature::operator+(double _temp) { diff --git a/src/Vector3Stats.cc b/src/Vector3Stats.cc index 10ad3a248..71b813772 100644 --- a/src/Vector3Stats.cc +++ b/src/Vector3Stats.cc @@ -15,22 +15,30 @@ * */ #include -#include "Vector3StatsPrivate.hh" using namespace ignition; using namespace math; -////////////////////////////////////////////////// -Vector3Stats::Vector3Stats() - : dataPtr(new Vector3StatsPrivate) +/// \brief Private data class for the Vector3Stats class. +class Vector3Stats::Implementation { -} + /// \brief Statistics for x component of signal. + public: SignalStats x; + + /// \brief Statistics for y component of signal. + public: SignalStats y; + + /// \brief Statistics for z component of signal. + public: SignalStats z; + + /// \brief Statistics for magnitude of signal. + public: SignalStats mag; +}; ////////////////////////////////////////////////// -Vector3Stats::~Vector3Stats() +Vector3Stats::Vector3Stats() + : dataPtr(ignition::utils::MakeImpl()) { - delete this->dataPtr; - this->dataPtr = 0; } ////////////////////////////////////////////////// diff --git a/src/Vector3StatsPrivate.hh b/src/Vector3StatsPrivate.hh deleted file mode 100644 index 6715876a9..000000000 --- a/src/Vector3StatsPrivate.hh +++ /dev/null @@ -1,48 +0,0 @@ -/* - * Copyright (C) 2015 Open Source Robotics Foundation - * - * Licensed under the Apache License, Version 2.0 (the "License"); - * you may not use this file except in compliance with the License. - * You may obtain a copy of the License at - * - * http://www.apache.org/licenses/LICENSE-2.0 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * -*/ -#ifndef IGNITION_MATH_VECTOR3STATSPRIVATE_HH_ -#define IGNITION_MATH_VECTOR3STATSPRIVATE_HH_ - -#include -#include - -namespace ignition -{ - namespace math - { - inline namespace IGNITION_MATH_VERSION_NAMESPACE - { - /// \brief Private data class for the Vector3Stats class. - class Vector3StatsPrivate - { - /// \brief Statistics for x component of signal. - public: SignalStats x; - - /// \brief Statistics for y component of signal. - public: SignalStats y; - - /// \brief Statistics for z component of signal. - public: SignalStats z; - - /// \brief Statistics for magnitude of signal. - public: SignalStats mag; - }; - } - } -} -#endif - From d2a8a34c54130dfdf2e761bc2b66f47d86066386 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 9 Dec 2021 11:12:21 -0600 Subject: [PATCH 2/9] Re-enable SWIG Signed-off-by: Michael Carroll --- src/CMakeLists.txt | 66 ++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 66 insertions(+) diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index f3bd16960..02e18e8e1 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -17,3 +17,69 @@ ign_build_tests(TYPE UNIT SOURCES ${gtest_sources}) # graph namespace add_subdirectory(graph) +################################################# +# Setup swig +if (SWIG_FOUND) + include(${SWIG_USE_FILE}) + set(CMAKE_SWIG_FLAGS "") + + include_directories(${PROJECT_SOURCE_DIR}/include) + + set(swig_files + ruby + Angle + GaussMarkovProcess + Helpers + Matrix3 + Pose3 + Quaternion + Rand + Temperature + Vector2 + Vector3 + Vector4) +endif() + +################################################# +# Create and install Ruby interfaces +# Example usage +# $ export RUBYLIB=/usr/local/lib/ruby +# $ ruby -e "require 'ignition/math'; a = Ignition::Math::Angle.new(20); puts a.Degree()" +if (RUBY_FOUND) + include_directories(${RUBY_INCLUDE_DIRS}) + + foreach (swig_file ${swig_files}) + # Assuming that each swig file has a test + list(APPEND ruby_tests ${swig_file}_TEST) + + # Generate the list if .i files + list(APPEND swig_i_files ${swig_file}.i) + + # Removing warning from auto-generated files. + set_source_files_properties(${swig_file}RUBY_wrap.cxx + PROPERTIES COMPILE_FLAGS "-w") + endforeach() + + # Turn on c++ + set_source_files_properties(${swig_i_files} PROPERTIES CPLUSPLUS ON) + + # Create the ruby library + + if(CMAKE_VERSION VERSION_GREATER 3.8.0) + SWIG_ADD_LIBRARY(math LANGUAGE ruby SOURCES ruby.i ${swig_i_files} ${sources}) + else() + SWIG_ADD_MODULE(math ruby ruby.i ${swig_i_files} ${sources}) + endif() + + SWIG_LINK_LIBRARIES(math ${RUBY_LIBRARY} + ignition-utils${IGN_UTILS_VER}::ignition-utils${IGN_UTILS_VER}) + target_compile_features(math PUBLIC ${IGN_CXX_${c++standard}_FEATURES}) + install(TARGETS math DESTINATION ${IGN_LIB_INSTALL_DIR}/ruby/ignition) + + # Add the ruby tests + foreach (test ${ruby_tests}) + add_test(NAME ${test}.rb COMMAND + ruby -I${CMAKE_BINARY_DIR}/lib ${CMAKE_SOURCE_DIR}/src/${test}.rb + --gtest_output=xml:${CMAKE_BINARY_DIR}/test_results/${test}rb.xml) + endforeach() +endif() From 148b95dfde24de5fee03bfffde2fc752fccafc4c Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 9 Dec 2021 11:15:09 -0600 Subject: [PATCH 3/9] Add ignition-utils to CI Signed-off-by: Michael Carroll --- .github/ci/packages.apt | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/ci/packages.apt b/.github/ci/packages.apt index ac2ae40d2..00191009e 100644 --- a/.github/ci/packages.apt +++ b/.github/ci/packages.apt @@ -1,4 +1,5 @@ libeigen3-dev libignition-cmake2-dev +libignition-utils1-dev ruby-dev swig From b59f8e2c528b5c4684fe37ebb793f350c15a5c51 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Mon, 13 Dec 2021 15:25:37 -0600 Subject: [PATCH 4/9] Address reviewer feedback Signed-off-by: Michael Carroll --- src/Frustum.cc | 3 --- src/Material_TEST.cc | 1 - 2 files changed, 4 deletions(-) diff --git a/src/Frustum.cc b/src/Frustum.cc index 937b901b1..749646137 100644 --- a/src/Frustum.cc +++ b/src/Frustum.cc @@ -27,9 +27,6 @@ using namespace math; /// \brief Private data for the Frustum class class Frustum::Implementation { - /// \param[in] _pose Pose of the frustum, which is the vertex (top of - /// the pyramid). - /// \brief Near distance /// This is the distance from the frustum's vertex to the closest plane public: double near {0}; diff --git a/src/Material_TEST.cc b/src/Material_TEST.cc index 72e3c682d..a62ff8ef7 100644 --- a/src/Material_TEST.cc +++ b/src/Material_TEST.cc @@ -100,7 +100,6 @@ TEST(MaterialTest, Accessors) // Test move constructor Material mat4(std::move(mat3)); EXPECT_EQ(mat2, mat4); - Material defaultMat; // Test move operator Material mat5; From e8d82f2c949809fa1a74bdbdf4a3769eacf3570e Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Tue, 21 Dec 2021 11:10:47 -0600 Subject: [PATCH 5/9] Clean up merge Signed-off-by: Michael Carroll --- include/ignition/math/PID.hh | 49 +-------- include/ignition/math/SignalStats.hh | 3 + src/PID.cc | 149 +++++++++++++++++---------- 3 files changed, 103 insertions(+), 98 deletions(-) diff --git a/include/ignition/math/PID.hh b/include/ignition/math/PID.hh index 59a41ad33..2899f8642 100644 --- a/include/ignition/math/PID.hh +++ b/include/ignition/math/PID.hh @@ -20,6 +20,7 @@ #include #include #include +#include namespace ignition { @@ -63,9 +64,6 @@ namespace ignition const double _cmdMin = 0.0, const double _cmdOffset = 0.0); - /// \brief Destructor - public: ~PID() = default; - /// \brief Initialize PID-gains and integral term /// limits:[iMax:iMin]-[I1:I2]. /// @@ -181,52 +179,11 @@ namespace ignition /// \param[in] _de The derivative error. public: void Errors(double &_pe, double &_ie, double &_de) const; - /// \brief Assignment operator - /// \param[in] _p a reference to a PID to assign values from - /// \return reference to this instance - public: PID &operator=(const PID &_p); - /// \brief Reset the errors and command. public: void Reset(); - /// \brief Error at a previous step. - private: double pErrLast = 0.0; - - /// \brief Current error. - private: double pErr = 0.0; - - /// \brief Integral of gain times error. - private: double iErr = 0.0; - - /// \brief Derivative error. - private: double dErr = 0.0; - - /// \brief Gain for proportional control. - private: double pGain; - - /// \brief Gain for integral control. - private: double iGain = 0.0; - - /// \brief Gain for derivative control. - private: double dGain = 0.0; - - /// \brief Maximum clamping value for integral term. - private: double iMax = -1.0; - - /// \brief Minim clamping value for integral term. - private: double iMin = 0.0; - - /// \brief Command value. - private: double cmd = 0.0; - - /// \brief Max command clamping value. - private: double cmdMax = -1.0; - - /// \brief Min command clamping value. - private: double cmdMin = 0.0; - - /// \brief Command offset. - private: double cmdOffset = 0.0; + /// \brief Pointer to private data. + IGN_UTILS_IMPL_PTR(dataPtr) }; } } diff --git a/include/ignition/math/SignalStats.hh b/include/ignition/math/SignalStats.hh index f2d87c4c0..af1e23d25 100644 --- a/include/ignition/math/SignalStats.hh +++ b/include/ignition/math/SignalStats.hh @@ -36,6 +36,9 @@ namespace ignition /// \brief Constructor public: SignalStatistic(); + /// \brief Destructor + public: virtual ~SignalStatistic() = default; + /// \brief Get the current value of the statistical measure. /// \return Current value of the statistical measure. public: virtual double Value() const = 0; diff --git a/src/PID.cc b/src/PID.cc index 37376635e..fa6dcf0a8 100644 --- a/src/PID.cc +++ b/src/PID.cc @@ -23,14 +23,56 @@ using namespace ignition; using namespace math; +///////////////////////////////////////////////// +class PID::Implementation +{ + /// \brief Error at a previous step. + public: double pErrLast = 0.0; + + /// \brief Current error. + public: double pErr = 0.0; + + /// \brief Integral of gain times error. + public: double iErr = 0.0; + + /// \brief Derivative error. + public: double dErr = 0.0; + + /// \brief Gain for proportional control. + public: double pGain; + + /// \brief Gain for integral control. + public: double iGain = 0.0; + + /// \brief Gain for derivative control. + public: double dGain = 0.0; + + /// \brief Maximum clamping value for integral term. + public: double iMax = -1.0; + + /// \brief Minim clamping value for integral term. + public: double iMin = 0.0; + + /// \brief Command value. + public: double cmd = 0.0; + + /// \brief Max command clamping value. + public: double cmdMax = -1.0; + + /// \brief Min command clamping value. + public: double cmdMin = 0.0; + + /// \brief Command offset. + public: double cmdOffset = 0.0; +}; + ///////////////////////////////////////////////// PID::PID(const double _p, const double _i, const double _d, const double _imax, const double _imin, const double _cmdMax, const double _cmdMin, const double _cmdOffset) -: pGain(_p), iGain(_i), dGain(_d), iMax(_imax), iMin(_imin), - cmdMax(_cmdMax), cmdMin(_cmdMin), cmdOffset(_cmdOffset) +: dataPtr(ignition::utils::MakeImpl()) { - this->Reset(); + this->Init(_p, _i, _d, _imax, _imin, _cmdMax, _cmdMin, _cmdOffset); } ///////////////////////////////////////////////// @@ -38,77 +80,74 @@ void PID::Init(const double _p, const double _i, const double _d, const double _imax, const double _imin, const double _cmdMax, const double _cmdMin, const double _cmdOffset) { - this->pGain = _p; - this->iGain = _i; - this->dGain = _d; - this->iMax = _imax; - this->iMin = _imin; - this->cmdMax = _cmdMax; - this->cmdMin = _cmdMin; - this->cmdOffset = _cmdOffset; + this->dataPtr->pGain = _p; + this->dataPtr->iGain = _i; + this->dataPtr->dGain = _d; + this->dataPtr->iMax = _imax; + this->dataPtr->iMin = _imin; + this->dataPtr->cmdMax = _cmdMax; + this->dataPtr->cmdMin = _cmdMin; + this->dataPtr->cmdOffset = _cmdOffset; this->Reset(); } -///////////////////////////////////////////////// -PID &PID::operator=(const PID &_p) = default; - ///////////////////////////////////////////////// void PID::SetPGain(const double _p) { - this->pGain = _p; + this->dataPtr->pGain = _p; } ///////////////////////////////////////////////// void PID::SetIGain(const double _i) { - this->iGain = _i; + this->dataPtr->iGain = _i; } ///////////////////////////////////////////////// void PID::SetDGain(const double _d) { - this->dGain = _d; + this->dataPtr->dGain = _d; } ///////////////////////////////////////////////// void PID::SetIMax(const double _i) { - this->iMax = _i; + this->dataPtr->iMax = _i; } ///////////////////////////////////////////////// void PID::SetIMin(const double _i) { - this->iMin = _i; + this->dataPtr->iMin = _i; } ///////////////////////////////////////////////// void PID::SetCmdMax(const double _c) { - this->cmdMax = _c; + this->dataPtr->cmdMax = _c; } ///////////////////////////////////////////////// void PID::SetCmdMin(const double _c) { - this->cmdMin = _c; + this->dataPtr->cmdMin = _c; } ///////////////////////////////////////////////// void PID::SetCmdOffset(const double _c) { - this->cmdOffset = _c; + this->dataPtr->cmdOffset = _c; } ///////////////////////////////////////////////// void PID::Reset() { - this->pErrLast = 0.0; - this->pErr = 0.0; - this->iErr = 0.0; - this->dErr = 0.0; - this->cmd = 0.0; + this->dataPtr->pErrLast = 0.0; + this->dataPtr->pErr = 0.0; + this->dataPtr->iErr = 0.0; + this->dataPtr->dErr = 0.0; + this->dataPtr->cmd = 0.0; } ///////////////////////////////////////////////// @@ -122,102 +161,108 @@ double PID::Update(const double _error, } double pTerm, dTerm; - this->pErr = _error; + this->dataPtr->pErr = _error; // Calculate proportional contribution to command - pTerm = this->pGain * this->pErr; + pTerm = this->dataPtr->pGain * this->dataPtr->pErr; // Calculate the integral error - this->iErr = this->iErr + this->iGain * _dt.count() * this->pErr; + this->dataPtr->iErr = this->dataPtr->iErr + + this->dataPtr->iGain * _dt.count() * this->dataPtr->pErr; // Check the integral limits // If enabled, this will limit iErr so that the limit is meaningful // in the output - if (this->iMax >= this->iMin) - this->iErr = clamp(this->iErr, this->iMin, this->iMax); + if (this->dataPtr->iMax >= this->dataPtr->iMin) + this->dataPtr->iErr = clamp(this->dataPtr->iErr, + this->dataPtr->iMin, + this->dataPtr->iMax); // Calculate the derivative error if (_dt != std::chrono::duration(0)) { - this->dErr = (this->pErr - this->pErrLast) / _dt.count(); - this->pErrLast = this->pErr; + this->dataPtr->dErr = + (this->dataPtr->pErr - this->dataPtr->pErrLast) / _dt.count(); + this->dataPtr->pErrLast = this->dataPtr->pErr; } // Calculate derivative contribution to command - dTerm = this->dGain * this->dErr; - this->cmd = this->cmdOffset -pTerm - this->iErr - dTerm; + dTerm = this->dataPtr->dGain * this->dataPtr->dErr; + this->dataPtr->cmd = + this->dataPtr->cmdOffset - pTerm - this->dataPtr->iErr - dTerm; // Check the command limits - if (this->cmdMax >= this->cmdMin) - this->cmd = clamp(this->cmd, this->cmdMin, this->cmdMax); + if (this->dataPtr->cmdMax >= this->dataPtr->cmdMin) + this->dataPtr->cmd = + clamp(this->dataPtr->cmd, this->dataPtr->cmdMin, this->dataPtr->cmdMax); - return this->cmd; + return this->dataPtr->cmd; } ///////////////////////////////////////////////// void PID::SetCmd(const double _cmd) { - this->cmd = _cmd; + this->dataPtr->cmd = _cmd; } ///////////////////////////////////////////////// double PID::Cmd() const { - return this->cmd; + return this->dataPtr->cmd; } ///////////////////////////////////////////////// void PID::Errors(double &_pe, double &_ie, double &_de) const { - _pe = this->pErr; - _ie = this->iErr; - _de = this->dErr; + _pe = this->dataPtr->pErr; + _ie = this->dataPtr->iErr; + _de = this->dataPtr->dErr; } ///////////////////////////////////////////////// double PID::PGain() const { - return this->pGain; + return this->dataPtr->pGain; } ///////////////////////////////////////////////// double PID::IGain() const { - return this->iGain; + return this->dataPtr->iGain; } ///////////////////////////////////////////////// double PID::DGain() const { - return this->dGain; + return this->dataPtr->dGain; } ///////////////////////////////////////////////// double PID::IMax() const { - return this->iMax; + return this->dataPtr->iMax; } ///////////////////////////////////////////////// double PID::IMin() const { - return this->iMin; + return this->dataPtr->iMin; } ///////////////////////////////////////////////// double PID::CmdMax() const { - return this->cmdMax; + return this->dataPtr->cmdMax; } ///////////////////////////////////////////////// double PID::CmdMin() const { - return this->cmdMin; + return this->dataPtr->cmdMin; } ///////////////////////////////////////////////// double PID::CmdOffset() const { - return this->cmdOffset; + return this->dataPtr->cmdOffset; } From e3e9e8e6f56ec68118cfa34d92938a904150fa16 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 22 Dec 2021 15:08:19 -0600 Subject: [PATCH 6/9] Update includes for Windows Signed-off-by: Michael Carroll --- src/Frustum.cc | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/src/Frustum.cc b/src/Frustum.cc index 749646137..fc3ac9f28 100644 --- a/src/Frustum.cc +++ b/src/Frustum.cc @@ -16,9 +16,15 @@ */ #include +#include +#include + +#include "ignition/math/Angle.hh" #include "ignition/math/AxisAlignedBox.hh" #include "ignition/math/Frustum.hh" #include "ignition/math/Matrix4.hh" +#include "ignition/math/Plane.hh" +#include "ignition/math/Pose3.hh" using namespace ignition; using namespace math; From 0dc9055d102368b5a0fde15c5851f576ccaf2d29 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Wed, 22 Dec 2021 15:50:41 -0600 Subject: [PATCH 7/9] Fix implementation for macOS Signed-off-by: Michael Carroll --- src/DiffDriveOdometry.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/DiffDriveOdometry.cc b/src/DiffDriveOdometry.cc index fd0096d7f..7bddee497 100644 --- a/src/DiffDriveOdometry.cc +++ b/src/DiffDriveOdometry.cc @@ -71,10 +71,10 @@ class ignition::math::DiffDriveOdometry::Implementation public: double rightWheelOldPos{0.0}; /// \brief Rolling mean accumulators for the linear velocity - public: RollingMean linearMean; + public: RollingMean linearMean {0}; /// \brief Rolling mean accumulators for the angular velocity - public: RollingMean angularMean; + public: RollingMean angularMean {0}; /// \brief Initialized flag. public: bool initialized{false}; From 184945b2ef44fb0a94bceb53c58a0d5a6db6b62e Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Thu, 23 Dec 2021 09:26:31 -0600 Subject: [PATCH 8/9] Fix coverage regression Signed-off-by: Michael Carroll --- src/DiffDriveOdometry.cc | 3 +-- src/DiffDriveOdometry_TEST.cc | 14 ++++++++++---- 2 files changed, 11 insertions(+), 6 deletions(-) diff --git a/src/DiffDriveOdometry.cc b/src/DiffDriveOdometry.cc index 7bddee497..74cfb2ebd 100644 --- a/src/DiffDriveOdometry.cc +++ b/src/DiffDriveOdometry.cc @@ -84,8 +84,7 @@ class ignition::math::DiffDriveOdometry::Implementation DiffDriveOdometry::DiffDriveOdometry(size_t _windowSize) : dataPtr(ignition::utils::MakeImpl()) { - this->dataPtr->linearMean.SetWindowSize(_windowSize); - this->dataPtr->angularMean.SetWindowSize(_windowSize); + this->SetVelocityRollingWindowSize(_windowSize); } ////////////////////////////////////////////////// diff --git a/src/DiffDriveOdometry_TEST.cc b/src/DiffDriveOdometry_TEST.cc index 6bc531f11..948f8b163 100644 --- a/src/DiffDriveOdometry_TEST.cc +++ b/src/DiffDriveOdometry_TEST.cc @@ -33,6 +33,7 @@ TEST(DiffDriveOdometryTest, DiffDriveOdometry) EXPECT_DOUBLE_EQ(0.0, odom.Y()); EXPECT_DOUBLE_EQ(0.0, odom.LinearVelocity()); EXPECT_DOUBLE_EQ(0.0, *odom.AngularVelocity()); + EXPECT_FALSE(odom.Initialized()); double wheelSeparation = 2.0; double wheelRadius = 0.5; @@ -45,11 +46,15 @@ TEST(DiffDriveOdometryTest, DiffDriveOdometry) odom.SetWheelParams(wheelSeparation, wheelRadius, wheelRadius); auto startTime = std::chrono::steady_clock::now(); odom.Init(startTime); + EXPECT_TRUE(odom.Initialized()); + + // Expect false if time difference is too small + EXPECT_FALSE(odom.Update(0.0, 0.0, startTime)); // Sleep for a little while, then update the odometry with the new wheel // position. auto time1 = startTime + std::chrono::milliseconds(100); - odom.Update(IGN_DTOR(1.0), IGN_DTOR(1.0), time1); + EXPECT_TRUE(odom.Update(IGN_DTOR(1.0), IGN_DTOR(1.0), time1)); EXPECT_DOUBLE_EQ(0.0, *odom.Heading()); EXPECT_DOUBLE_EQ(distPerDegree, odom.X()); EXPECT_DOUBLE_EQ(0.0, odom.Y()); @@ -61,7 +66,7 @@ TEST(DiffDriveOdometryTest, DiffDriveOdometry) // Sleep again, then update the odometry with the new wheel position. auto time2 = time1 + std::chrono::milliseconds(100); - odom.Update(IGN_DTOR(2.0), IGN_DTOR(2.0), time2); + EXPECT_TRUE(odom.Update(IGN_DTOR(2.0), IGN_DTOR(2.0), time2)); EXPECT_DOUBLE_EQ(0.0, *odom.Heading()); EXPECT_NEAR(distPerDegree * 2.0, odom.X(), 3e-6); EXPECT_DOUBLE_EQ(0.0, odom.Y()); @@ -79,10 +84,11 @@ TEST(DiffDriveOdometryTest, DiffDriveOdometry) EXPECT_DOUBLE_EQ(0.0, odom.Y()); EXPECT_DOUBLE_EQ(0.0, odom.LinearVelocity()); EXPECT_DOUBLE_EQ(0.0, *odom.AngularVelocity()); + EXPECT_TRUE(odom.Initialized()); // Sleep again, this time move 2 degrees in 100ms. time1 = startTime + std::chrono::milliseconds(100); - odom.Update(IGN_DTOR(2.0), IGN_DTOR(2.0), time1); + EXPECT_TRUE(odom.Update(IGN_DTOR(2.0), IGN_DTOR(2.0), time1)); EXPECT_DOUBLE_EQ(0.0, *odom.Heading()); EXPECT_NEAR(distPerDegree * 2.0, odom.X(), 3e-6); EXPECT_DOUBLE_EQ(0.0, odom.Y()); @@ -95,7 +101,7 @@ TEST(DiffDriveOdometryTest, DiffDriveOdometry) // Sleep again, this time rotate the right wheel by 1 degree. time2 = time1 + std::chrono::milliseconds(100); - odom.Update(IGN_DTOR(2.0), IGN_DTOR(3.0), time2); + EXPECT_TRUE(odom.Update(IGN_DTOR(2.0), IGN_DTOR(3.0), time2)); // The heading should be the arc tangent of the linear distance traveled // by the right wheel (the left wheel was stationary) divided by the // wheel separation. From 5ddf3df9a2fd97549b7d9dce0084a6cf3472eabe Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Fri, 7 Jan 2022 13:57:17 -0600 Subject: [PATCH 9/9] Revert SignalStats changes Signed-off-by: Michael Carroll --- include/ignition/math/SignalStats.hh | 53 +++++++++++++++++++++++----- src/SignalStats.cc | 32 +++++++++++++++-- src/SignalStatsPrivate.hh | 22 ++++++++++-- 3 files changed, 94 insertions(+), 13 deletions(-) diff --git a/include/ignition/math/SignalStats.hh b/include/ignition/math/SignalStats.hh index af1e23d25..2e1924ebe 100644 --- a/include/ignition/math/SignalStats.hh +++ b/include/ignition/math/SignalStats.hh @@ -18,10 +18,10 @@ #define IGNITION_MATH_SIGNALSTATS_HH_ #include +#include #include #include #include -#include namespace ignition { @@ -29,6 +29,10 @@ namespace ignition { // Inline bracket to help doxygen filtering. inline namespace IGNITION_MATH_VERSION_NAMESPACE { + // + /// \brief Forward declare private data class. + class SignalStatisticPrivate; + /// \class SignalStatistic SignalStats.hh ignition/math/SignalStats.hh /// \brief Statistical properties of a discrete time scalar signal. class IGNITION_MATH_VISIBLE SignalStatistic @@ -37,7 +41,11 @@ namespace ignition public: SignalStatistic(); /// \brief Destructor - public: virtual ~SignalStatistic() = default; + public: virtual ~SignalStatistic(); + + /// \brief Copy constructor + /// \param[in] _ss SignalStatistic to copy + public: SignalStatistic(const SignalStatistic &_ss); /// \brief Get the current value of the statistical measure. /// \return Current value of the statistical measure. @@ -58,13 +66,17 @@ namespace ignition /// \brief Forget all previous data. public: virtual void Reset(); - public: class Implementation; - IGN_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING +#ifdef _WIN32 +// Disable warning C4251 which is triggered by +// std::unique_ptr +#pragma warning(push) +#pragma warning(disable: 4251) +#endif /// \brief Pointer to private data. - /// Not using macros as it needs to be protected to be accessed from - /// derived classes - protected: ::ignition::utils::ImplPtr dataPtr; - IGN_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING + protected: std::unique_ptr dataPtr; +#ifdef _WIN32 +#pragma warning(pop) +#endif }; /// \class SignalMaximum SignalStats.hh ignition/math/SignalStats.hh @@ -162,6 +174,8 @@ namespace ignition public: virtual void InsertData(const double _data) override; }; + /// \brief Forward declare private data class. + class SignalStatsPrivate; /// \class SignalStats SignalStats.hh ignition/math/SignalStats.hh /// \brief Collection of statistics for a scalar signal. @@ -170,6 +184,13 @@ namespace ignition /// \brief Constructor public: SignalStats(); + /// \brief Destructor + public: ~SignalStats(); + + /// \brief Copy constructor + /// \param[in] _ss SignalStats to copy + public: SignalStats(const SignalStats &_ss); + /// \brief Get number of data points in first statistic. /// Technically you can have different numbers of data points /// in each statistic if you call InsertStatistic after InsertData, @@ -210,8 +231,22 @@ namespace ignition /// \brief Forget all previous data. public: void Reset(); + /// \brief Assignment operator + /// \param[in] _s A SignalStats to copy + /// \return this + public: SignalStats &operator=(const SignalStats &_s); + +#ifdef _WIN32 +// Disable warning C4251 which is triggered by +// std::unique_ptr +#pragma warning(push) +#pragma warning(disable: 4251) +#endif /// \brief Pointer to private data. - IGN_UTILS_IMPL_PTR(dataPtr) + private: std::unique_ptr dataPtr; +#ifdef _WIN32 +#pragma warning(pop) +#endif }; } } diff --git a/src/SignalStats.cc b/src/SignalStats.cc index 7d43254fc..4523bef3a 100644 --- a/src/SignalStats.cc +++ b/src/SignalStats.cc @@ -24,13 +24,24 @@ using namespace math; ////////////////////////////////////////////////// SignalStatistic::SignalStatistic() - : dataPtr(ignition::utils::MakeImpl()) + : dataPtr(new SignalStatisticPrivate) { this->dataPtr->data = 0.0; this->dataPtr->extraData = 0.0; this->dataPtr->count = 0; } +////////////////////////////////////////////////// +SignalStatistic::~SignalStatistic() +{ +} + +////////////////////////////////////////////////// +SignalStatistic::SignalStatistic(const SignalStatistic &_ss) + : dataPtr(_ss.dataPtr->Clone()) +{ +} + ////////////////////////////////////////////////// size_t SignalStatistic::Count() const { @@ -195,7 +206,18 @@ void SignalVariance::InsertData(const double _data) ////////////////////////////////////////////////// SignalStats::SignalStats() - : dataPtr(ignition::utils::MakeImpl()) + : dataPtr(new SignalStatsPrivate) +{ +} + +////////////////////////////////////////////////// +SignalStats::~SignalStats() +{ +} + +////////////////////////////////////////////////// +SignalStats::SignalStats(const SignalStats &_ss) + : dataPtr(_ss.dataPtr->Clone()) { } @@ -329,3 +351,9 @@ void SignalStats::Reset() } } +////////////////////////////////////////////////// +SignalStats &SignalStats::operator=(const SignalStats &_s) +{ + this->dataPtr = _s.dataPtr->Clone(); + return *this; +} diff --git a/src/SignalStatsPrivate.hh b/src/SignalStatsPrivate.hh index 2f408e7c7..e5e045e86 100644 --- a/src/SignalStatsPrivate.hh +++ b/src/SignalStatsPrivate.hh @@ -28,7 +28,7 @@ namespace ignition inline namespace IGNITION_MATH_VERSION_NAMESPACE { /// \brief Private data class for the SignalStatistic class. - class SignalStatistic::Implementation + class SignalStatisticPrivate { /// \brief Scalar representation of signal data. public: double data; @@ -39,6 +39,15 @@ namespace ignition /// \brief Count of data values in mean. public: unsigned int count; + + /// \brief Clone the SignalStatisticPrivate object. Used for implementing + /// copy semantics. + public: std::unique_ptr Clone() const + { + std::unique_ptr dataPtr( + new SignalStatisticPrivate(*this)); + return dataPtr; + } }; class SignalStatistic; @@ -52,10 +61,19 @@ namespace ignition typedef std::vector SignalStatistic_V; /// \brief Private data class for the SignalStats class. - class SignalStats::Implementation + class SignalStatsPrivate { /// \brief Vector of `SignalStatistic`s. public: SignalStatistic_V stats; + + /// \brief Clone the SignalStatsPrivate object. Used for implementing + /// copy semantics. + public: std::unique_ptr Clone() const + { + std::unique_ptr dataPtr( + new SignalStatsPrivate(*this)); + return dataPtr; + } }; } }