From 69945e29b953237d48415cdf902a93272054f92b Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Thu, 25 Jul 2024 20:35:54 -0500 Subject: [PATCH 1/2] Implement rule of zero Signed-off-by: Addisu Z. Taddese --- include/gz/math/Color.hh | 12 ----- include/gz/math/Inertial.hh | 12 ----- include/gz/math/Line3.hh | 9 ---- include/gz/math/MassMatrix3.hh | 13 ------ include/gz/math/Matrix3.hh | 12 ----- include/gz/math/Matrix4.hh | 12 ----- include/gz/math/Matrix6.hh | 9 ---- include/gz/math/OrientedBox.hh | 12 ----- include/gz/math/Plane.hh | 12 ----- include/gz/math/Pose3.hh | 11 ----- include/gz/math/Quaternion.hh | 12 ----- include/gz/math/SignalStats.hh | 48 +++----------------- include/gz/math/Vector2.hh | 12 ----- include/gz/math/Vector3.hh | 12 ----- include/gz/math/Vector4.hh | 12 ----- src/SignalStats.cc | 62 +++++++++++++------------- src/SignalStatsPrivate.hh | 81 ---------------------------------- 17 files changed, 36 insertions(+), 317 deletions(-) delete mode 100644 src/SignalStatsPrivate.hh diff --git a/include/gz/math/Color.hh b/include/gz/math/Color.hh index 4e5f97b38..92a0efff3 100644 --- a/include/gz/math/Color.hh +++ b/include/gz/math/Color.hh @@ -107,13 +107,6 @@ namespace gz::math this->Clamp(); } - /// \brief Copy Constructor - /// \param[in] _clr Color to copy - public: Color(const Color &_clr) = default; - - /// \brief Destructor - public: ~Color() = default; - /// \brief Reset the color to default values to red=0, green=0, /// blue=0, alpha=1. public: void Reset(); @@ -147,11 +140,6 @@ namespace gz::math /// \param[in] _v value public: void SetFromYUV(const float _y, const float _u, const float _v); - /// \brief Equal operator - /// \param[in] _pt Color to copy - /// \return Reference to this color - public: Color &operator=(const Color &_pt) = default; - /// \brief Array index operator /// \param[in] _index Color component index(0=red, 1=green, 2=blue, /// 3=alpha) diff --git a/include/gz/math/Inertial.hh b/include/gz/math/Inertial.hh index 025ca4b31..366eaccab 100644 --- a/include/gz/math/Inertial.hh +++ b/include/gz/math/Inertial.hh @@ -84,13 +84,6 @@ namespace gz::math : massMatrix(_massMatrix), pose(_pose), addedMass(_addedMass) {} - /// \brief Copy constructor. - /// \param[in] _inertial Inertial element to copy - public: Inertial(const Inertial &_inertial) = default; - - /// \brief Destructor. - public: ~Inertial() = default; - /// \brief Set the mass and inertia matrix. /// /// \param[in] _m New MassMatrix3 object. @@ -255,11 +248,6 @@ namespace gz::math return this->massMatrix.SetMoi(R * diag * R.Transposed()); } - /// \brief Equal operator. - /// \param[in] _inertial Inertial to copy. - /// \return Reference to this object. - public: Inertial &operator=(const Inertial &_inertial) = default; - /// \brief Equality comparison operator. /// \param[in] _inertial Inertial to copy. /// \return true if each component is equal within a default tolerance, diff --git a/include/gz/math/Line3.hh b/include/gz/math/Line3.hh index 0a3bcf0ef..b63fe8de3 100644 --- a/include/gz/math/Line3.hh +++ b/include/gz/math/Line3.hh @@ -35,10 +35,6 @@ namespace gz::math /// \brief Line Constructor public: Line3() = default; - /// \brief Copy constructor - /// \param[in] _line a line object - public: Line3(const Line3 &_line) = default; - /// \brief Constructor. /// \param[in] _ptA Start point of the line segment /// \param[in] _ptB End point of the line segment @@ -394,11 +390,6 @@ namespace gz::math return _out; } - /// \brief Assignment operator - /// \param[in] _line a new value - /// \return this - public: Line3 &operator=(const Line3 &_line) = default; - /// \brief Vector for storing the start and end points of the line private: math::Vector3 pts[2]; }; diff --git a/include/gz/math/MassMatrix3.hh b/include/gz/math/MassMatrix3.hh index f28446a69..a4b8fe15b 100644 --- a/include/gz/math/MassMatrix3.hh +++ b/include/gz/math/MassMatrix3.hh @@ -58,13 +58,6 @@ namespace gz::math : mass(_mass), Ixxyyzz(_ixxyyzz), Ixyxzyz(_ixyxzyz) {} - /// \brief Copy constructor. - /// \param[in] _m MassMatrix3 element to copy - public: MassMatrix3(const MassMatrix3 &_m) = default; - - /// \brief Destructor. - public: ~MassMatrix3() = default; - /// \brief Set the mass. /// \param[in] _m New mass value. /// \return True if the MassMatrix3 is valid. @@ -251,12 +244,6 @@ namespace gz::math return this->IsValid(); } - /// \brief Equal operator. - /// \param[in] _massMatrix MassMatrix3 to copy. - /// \return Reference to this object. - public: MassMatrix3 &operator=(const MassMatrix3 &_massMatrix) - = default; - /// \brief Equality comparison operator. /// \param[in] _m MassMatrix3 to copy. /// \return true if each component is equal within a default tolerance, diff --git a/include/gz/math/Matrix3.hh b/include/gz/math/Matrix3.hh index 18e70387b..3f27b072b 100644 --- a/include/gz/math/Matrix3.hh +++ b/include/gz/math/Matrix3.hh @@ -105,10 +105,6 @@ namespace gz::math std::memset(this->data, 0, sizeof(this->data[0][0])*9); } - /// \brief Copy constructor. - /// \param _m Matrix to copy - public: Matrix3(const Matrix3 &_m) = default; - /// \brief Construct a matrix3 using nine values. /// \param[in] _v00 Row 0, Col 0 value /// \param[in] _v01 Row 0, Col 1 value @@ -145,9 +141,6 @@ namespace gz::math 1 - 2 * qt.X()*qt.X() - 2 * qt.Y()*qt.Y()); } - /// \brief Desctructor - public: ~Matrix3() = default; - /// \brief Set a single value. /// \param[in] _row row index. _row is clamped to the range [0,2] /// \param[in] _col column index. _col is clamped to the range [0,2] @@ -274,11 +267,6 @@ namespace gz::math this->data[2][c] = _v.Z(); } - /// \brief Equal operator. this = _mat - /// \param _mat Matrix to copy. - /// \return This matrix. - public: Matrix3 &operator=(const Matrix3 &_mat) = default; - /// \brief Subtraction operator. /// \param[in] _m Matrix to subtract. /// \return The element wise difference of two matrices. diff --git a/include/gz/math/Matrix4.hh b/include/gz/math/Matrix4.hh index 24834096d..e873a46f3 100644 --- a/include/gz/math/Matrix4.hh +++ b/include/gz/math/Matrix4.hh @@ -47,10 +47,6 @@ namespace gz::math memset(this->data, 0, sizeof(this->data[0][0])*16); } - /// \brief Copy constructor - /// \param _m Matrix to copy - public: Matrix4(const Matrix4 &_m) = default; - /// \brief Constructor /// \param[in] _v00 Row 0, Col 0 value /// \param[in] _v01 Row 0, Col 1 value @@ -110,9 +106,6 @@ namespace gz::math this->SetTranslation(_pose.Pos()); } - /// \brief Destructor - public: ~Matrix4() = default; - /// \brief Change the values /// \param[in] _v00 Row 0, Col 0 value /// \param[in] _v01 Row 0, Col 1 value @@ -539,11 +532,6 @@ namespace gz::math this->data[0][3], this->data[1][3], this->data[2][3], this->data[3][3]); } - /// \brief Equal operator. this = _mat - /// \param _mat Incoming matrix - /// \return itself - public: Matrix4 &operator=(const Matrix4 &_mat) = default; - /// \brief Equal operator for 3x3 matrix /// \param _mat Incoming matrix /// \return itself diff --git a/include/gz/math/Matrix6.hh b/include/gz/math/Matrix6.hh index b6aeae29e..b2d024cce 100644 --- a/include/gz/math/Matrix6.hh +++ b/include/gz/math/Matrix6.hh @@ -67,10 +67,6 @@ namespace gz::math memset(this->data, 0, sizeof(this->data[0][0])*MatrixSize*MatrixSize); } - /// \brief Copy constructor - /// \param _m Matrix to copy - public: Matrix6(const Matrix6 &_m) = default; - /// \brief Constructor /// \param[in] _v00 Row 0, Col 0 value /// \param[in] _v01 Row 0, Col 1 value @@ -294,11 +290,6 @@ namespace gz::math this->data[5][5]); } - /// \brief Assignment operator. this = _mat - /// \param _mat Incoming matrix - /// \return itself - public: Matrix6 &operator=(const Matrix6 &_mat) = default; - /// \brief Multiplication assignment operator. This matrix will /// become equal to this * _m2. /// \param[in] _m2 Incoming matrix. diff --git a/include/gz/math/OrientedBox.hh b/include/gz/math/OrientedBox.hh index cc0ff4583..1521e2680 100644 --- a/include/gz/math/OrientedBox.hh +++ b/include/gz/math/OrientedBox.hh @@ -79,13 +79,6 @@ namespace gz::math { } - /// \brief Copy constructor. - /// \param[in] _b OrientedBox to copy. - public: OrientedBox(const OrientedBox &_b) = default; - - /// \brief Destructor - public: ~OrientedBox() = default; - /// \brief Get the length along the x dimension /// \return Value of the length in the x dimension public: T XLength() const @@ -137,11 +130,6 @@ namespace gz::math this->pose = _pose; } - /// \brief Assignment operator. Set this box to the parameter - /// \param[in] _b OrientedBox to copy - /// \return The new box. - public: OrientedBox &operator=(const OrientedBox &_b) = default; - /// \brief Equality test operator /// \param[in] _b OrientedBox to test /// \return True if equal diff --git a/include/gz/math/Plane.hh b/include/gz/math/Plane.hh index 12b95471f..73fb5714c 100644 --- a/include/gz/math/Plane.hh +++ b/include/gz/math/Plane.hh @@ -79,13 +79,6 @@ namespace gz::math this->Set(_normal, _size, _offset); } - /// \brief Copy constructor - /// \param[in] _plane Plane to copy - public: Plane(const Plane &_plane) = default; - - /// \brief Destructor - public: ~Plane() = default; - /// \brief Set the plane /// \param[in] _normal The plane normal /// \param[in] _offset Offset along the normal @@ -255,11 +248,6 @@ namespace gz::math return this->d; } - /// \brief Equal operator - /// \param _p another plane - /// \return itself - public: Plane &operator=(const Plane &_p) = default; - /// \brief Plane normal private: Vector3 normal; diff --git a/include/gz/math/Pose3.hh b/include/gz/math/Pose3.hh index 7b6903a19..4b1969f67 100644 --- a/include/gz/math/Pose3.hh +++ b/include/gz/math/Pose3.hh @@ -114,13 +114,6 @@ namespace gz::math { } - /// \brief Copy constructor. - /// \param[in] _pose Pose3 to copy - public: Pose3(const Pose3 &_pose) = default; - - /// \brief Destructor. - public: ~Pose3() = default; - /// \brief Set the pose from a Vector3 and a Quaternion /// \param[in] _pos The position. /// \param[in] _rot The rotation. @@ -212,10 +205,6 @@ namespace gz::math return *this; } - /// \brief Assignment operator - /// \param[in] _pose Pose3 to copy - public: Pose3 &operator=(const Pose3 &_pose) = default; - /// \brief Add one point to a vector: result = this + pos. /// \param[in] _pos Position to add to this pose /// \return The resulting position. diff --git a/include/gz/math/Quaternion.hh b/include/gz/math/Quaternion.hh index ac7fb920a..31f5956b8 100644 --- a/include/gz/math/Quaternion.hh +++ b/include/gz/math/Quaternion.hh @@ -142,18 +142,6 @@ namespace gz::math this->SetFromMatrix(_mat); } - /// \brief Copy constructor. This constructor does not normalize the - /// quaternion. - /// \param[in] _qt Quaternion to copy - public: Quaternion(const Quaternion &_qt) = default; - - /// \brief Destructor - public: ~Quaternion() = default; - - /// \brief Assignment operator - /// \param[in] _qt Quaternion to copy - public: Quaternion &operator=(const Quaternion &_qt) = default; - /// \brief Invert the quaternion. The quaternion is first normalized, /// then inverted. public: void Invert() diff --git a/include/gz/math/SignalStats.hh b/include/gz/math/SignalStats.hh index ec7af1404..4bace7fbe 100644 --- a/include/gz/math/SignalStats.hh +++ b/include/gz/math/SignalStats.hh @@ -22,6 +22,7 @@ #include #include #include +#include namespace gz::math { @@ -38,13 +39,6 @@ namespace gz::math /// \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; @@ -64,17 +58,11 @@ namespace gz::math /// \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 /// \brief Pointer to private data. - protected: std::unique_ptr dataPtr; -#ifdef _WIN32 -#pragma warning(pop) -#endif + public: class Implementation; + GZ_UTILS_WARN_IGNORE__DLL_INTERFACE_MISSING + protected: ::gz::utils::ImplPtr dataPtr; + GZ_UTILS_WARN_RESUME__DLL_INTERFACE_MISSING }; /// \class SignalMaximum SignalStats.hh gz/math/SignalStats.hh @@ -172,9 +160,6 @@ namespace gz::math public: virtual void InsertData(const double _data) override; }; - /// \brief Forward declare private data class. - class SignalStatsPrivate; - /// \class SignalStats SignalStats.hh gz/math/SignalStats.hh /// \brief Collection of statistics for a scalar signal. class GZ_MATH_VISIBLE SignalStats @@ -182,13 +167,6 @@ namespace gz::math /// \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, @@ -229,22 +207,8 @@ namespace gz::math /// \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 + GZ_UTILS_IMPL_PTR(dataPtr) }; } // namespace GZ_MATH_VERSION_NAMESPACE } // namespace gz::math diff --git a/include/gz/math/Vector2.hh b/include/gz/math/Vector2.hh index 031582bbe..37ef348a7 100644 --- a/include/gz/math/Vector2.hh +++ b/include/gz/math/Vector2.hh @@ -59,13 +59,6 @@ namespace gz::math { } - /// \brief Copy constructor - /// \param[in] _v the value - public: Vector2(const Vector2 &_v) = default; - - /// \brief Destructor - public: ~Vector2() = default; - /// \brief Return the sum of the values /// \return the sum public: T Sum() const @@ -219,11 +212,6 @@ namespace gz::math return std::min(this->data[0], this->data[1]); } - /// \brief Assignment operator - /// \param[in] _v a value for x and y element - /// \return this - public: Vector2 &operator=(const Vector2 &_v) = default; - /// \brief Assignment operator /// \param[in] _v the value for x and y element /// \return this diff --git a/include/gz/math/Vector3.hh b/include/gz/math/Vector3.hh index 00d58ec8f..1bbfa5fb4 100644 --- a/include/gz/math/Vector3.hh +++ b/include/gz/math/Vector3.hh @@ -71,13 +71,6 @@ namespace gz::math { } - /// \brief Copy constructor - /// \param[in] _v a vector - public: Vector3(const Vector3 &_v) = default; - - /// \brief Destructor - public: ~Vector3() = default; - /// \brief Return the sum of the values /// \return the sum public: T Sum() const @@ -322,11 +315,6 @@ namespace gz::math return min; } - /// \brief Assignment operator - /// \param[in] _v a new value - /// \return this - public: Vector3 &operator=(const Vector3 &_v) = default; - /// \brief Assignment operator /// \param[in] _v assigned to all elements /// \return this diff --git a/include/gz/math/Vector4.hh b/include/gz/math/Vector4.hh index c27a370e6..a57b73f69 100644 --- a/include/gz/math/Vector4.hh +++ b/include/gz/math/Vector4.hh @@ -61,13 +61,6 @@ namespace gz::math { } - /// \brief Copy constructor - /// \param[in] _v vector - public: Vector4(const Vector4 &_v) = default; - - /// \brief Destructor - public: ~Vector4() = default; - /// \brief Calc distance to the given point /// \param[in] _pt the point /// \return the distance @@ -258,11 +251,6 @@ namespace gz::math return this->data[0] + this->data[1] + this->data[2] + this->data[3]; } - /// \brief Assignment operator - /// \param[in] _v the vector - /// \return a reference to this vector - public: Vector4 &operator=(const Vector4 &_v) = default; - /// \brief Assignment operator /// \param[in] _value public: Vector4 &operator=(T _value) diff --git a/src/SignalStats.cc b/src/SignalStats.cc index 151c40d85..4a4aa9e57 100644 --- a/src/SignalStats.cc +++ b/src/SignalStats.cc @@ -17,31 +17,47 @@ #include #include #include -#include "SignalStatsPrivate.hh" using namespace gz; using namespace math; +/// \brief Private data class for the SignalStatistic class. +class SignalStatistic::Implementation +{ + /// \brief Scalar representation of signal data. + public: double data; + + /// \brief Scalar representation of extra signal data. + /// For example, the standard deviation statistic needs an extra variable. + public: double extraData; + + /// \brief Count of data values in mean. + public: unsigned int count; +}; + +/// \def SignalStatisticPtr +/// \brief Shared pointer to SignalStatistic object +typedef std::shared_ptr SignalStatisticPtr; + +/// \def SignalStatistic_V +/// \brief Vector of SignalStatisticPtr +typedef std::vector SignalStatistic_V; + +/// \brief Private data class for the SignalStats class. +class SignalStats::Implementation +{ + /// \brief Vector of `SignalStatistic`s. + public: SignalStatistic_V stats; +}; ////////////////////////////////////////////////// SignalStatistic::SignalStatistic() - : dataPtr(new SignalStatisticPrivate) + : dataPtr(gz::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 +222,7 @@ void SignalVariance::InsertData(const double _data) ////////////////////////////////////////////////// SignalStats::SignalStats() - : dataPtr(new SignalStatsPrivate) -{ -} - -////////////////////////////////////////////////// -SignalStats::~SignalStats() -{ -} - -////////////////////////////////////////////////// -SignalStats::SignalStats(const SignalStats &_ss) - : dataPtr(_ss.dataPtr->Clone()) + : dataPtr(gz::utils::MakeImpl()) { } @@ -350,10 +355,3 @@ void SignalStats::Reset() statistic->Reset(); } } - -////////////////////////////////////////////////// -SignalStats &SignalStats::operator=(const SignalStats &_s) -{ - this->dataPtr = _s.dataPtr->Clone(); - return *this; -} diff --git a/src/SignalStatsPrivate.hh b/src/SignalStatsPrivate.hh deleted file mode 100644 index ccb914cab..000000000 --- a/src/SignalStatsPrivate.hh +++ /dev/null @@ -1,81 +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 GZ_MATH_SIGNALSTATSPRIVATE_HH_ -#define GZ_MATH_SIGNALSTATSPRIVATE_HH_ - -#include -#include -#include - -namespace gz -{ - namespace math - { - inline namespace GZ_MATH_VERSION_NAMESPACE - { - /// \brief Private data class for the SignalStatistic class. - class SignalStatisticPrivate - { - /// \brief Scalar representation of signal data. - public: double data; - - /// \brief Scalar representation of extra signal data. - /// For example, the standard deviation statistic needs an extra variable. - public: double extraData; - - /// \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; - - /// \def SignalStatisticPtr - /// \brief Shared pointer to SignalStatistic object - typedef std::shared_ptr SignalStatisticPtr; - - /// \def SignalStatistic_V - /// \brief Vector of SignalStatisticPtr - typedef std::vector SignalStatistic_V; - - /// \brief Private data class for the SignalStats class. - 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; - } - }; - } - } -} -#endif From 455dcb2e769494cdbf650234a64de90e03929035 Mon Sep 17 00:00:00 2001 From: "Addisu Z. Taddese" Date: Tue, 6 Aug 2024 11:51:37 -0500 Subject: [PATCH 2/2] Declare all special member functions as defaulted in SignalStatistic Signed-off-by: Addisu Z. Taddese --- include/gz/math/SignalStats.hh | 25 +++++++++++++++++++++++++ 1 file changed, 25 insertions(+) diff --git a/include/gz/math/SignalStats.hh b/include/gz/math/SignalStats.hh index 4bace7fbe..160e3d681 100644 --- a/include/gz/math/SignalStats.hh +++ b/include/gz/math/SignalStats.hh @@ -39,6 +39,31 @@ namespace gz::math /// \brief Constructor public: SignalStatistic(); + /// \brief Destructor + public: virtual ~SignalStatistic() = default; + + // Since we have to declare the destructor virtual, we have to declare the + // all the special member functions as defaulted. + // See https://en.cppreference.com/w/cpp/language/rule_of_three + + /// \brief Copy constructor + /// \param[in] _ss SignalStatistic to copy + public: SignalStatistic(const SignalStatistic &_ss) = default; + + /// \brief Move constructor + /// \param[in] _ss SignalStatistic to move + public: SignalStatistic(SignalStatistic &&_ss) = default; + + /// \brief Assignment operator + /// \param[in] _s A SignalStatistic to copy + /// \return this + public: SignalStatistic &operator=(const SignalStatistic &_s) = default; + + /// \brief Move assignment operator + /// \param[in] _s A SignalStatistic to copy + /// \return this + public: SignalStatistic &operator=(SignalStatistic &&_s) = default; + /// \brief Get the current value of the statistical measure. /// \return Current value of the statistical measure. public: virtual double Value() const = 0;