diff --git a/Changelog.md b/Changelog.md index 04889d290..9817d2329 100644 --- a/Changelog.md +++ b/Changelog.md @@ -30,6 +30,9 @@ 1. Evict large function definitions from the Helpers.hh header file. * [Pull request 288](https://github.com/ignitionrobotics/ign-math/pull/288) +1. Remove virtual from destructors of copyable classes. + * [Pull request 293](https://github.com/ignitionrobotics/ign-math/pull/293) + ## Ignition Math 6.x ### Ignition Math 6.x.x diff --git a/include/ignition/math/AxisAlignedBox.hh b/include/ignition/math/AxisAlignedBox.hh index 81bc1c1a6..19bb8ce2e 100644 --- a/include/ignition/math/AxisAlignedBox.hh +++ b/include/ignition/math/AxisAlignedBox.hh @@ -71,7 +71,7 @@ namespace ignition public: AxisAlignedBox(const AxisAlignedBox &_b); /// \brief Destructor - public: virtual ~AxisAlignedBox(); + public: ~AxisAlignedBox(); /// \brief Get the length along the x dimension /// \return Double value of the length in the x dimension diff --git a/include/ignition/math/Box.hh b/include/ignition/math/Box.hh index 8074303c3..86990fdfe 100644 --- a/include/ignition/math/Box.hh +++ b/include/ignition/math/Box.hh @@ -84,10 +84,10 @@ namespace ignition /// \brief Copy Constructor. /// \param[in] _b Box to copy. - public: Box(const Box &_b); + public: Box(const Box &_b) = default; /// \brief Destructor. - public: virtual ~Box() = default; + public: ~Box() = default; /// \brief Get the size of the box. /// \return Size of the box in meters. diff --git a/include/ignition/math/Color.hh b/include/ignition/math/Color.hh index 6d8131407..abc8675eb 100644 --- a/include/ignition/math/Color.hh +++ b/include/ignition/math/Color.hh @@ -86,7 +86,7 @@ namespace ignition public: Color(const Color &_clr); /// \brief Destructor - public: virtual ~Color(); + public: ~Color(); /// \brief Reset the color to default values to red=0, green=0, /// blue=0, alpha=1. diff --git a/include/ignition/math/Frustum.hh b/include/ignition/math/Frustum.hh index d297490cd..b85e23f2a 100644 --- a/include/ignition/math/Frustum.hh +++ b/include/ignition/math/Frustum.hh @@ -91,7 +91,7 @@ namespace ignition public: Frustum(const Frustum &_p); /// \brief Destructor - public: virtual ~Frustum(); + public: ~Frustum(); /// \brief Get the near distance. This is the distance from the /// frustum's vertex to the closest plane. diff --git a/include/ignition/math/Inertial.hh b/include/ignition/math/Inertial.hh index e15d96779..00a133ff1 100644 --- a/include/ignition/math/Inertial.hh +++ b/include/ignition/math/Inertial.hh @@ -64,12 +64,10 @@ namespace ignition /// \brief Copy constructor. /// \param[in] _inertial Inertial element to copy - public: Inertial(const Inertial &_inertial) - : massMatrix(_inertial.MassMatrix()), pose(_inertial.Pose()) - {} + public: Inertial(const Inertial &_inertial) = default; /// \brief Destructor. - public: virtual ~Inertial() {} + public: ~Inertial() = default; /// \brief Set the mass and inertia matrix. /// @@ -166,13 +164,7 @@ namespace ignition /// \brief Equal operator. /// \param[in] _inertial Inertial to copy. /// \return Reference to this object. - public: Inertial &operator=(const Inertial &_inertial) - { - this->massMatrix = _inertial.MassMatrix(); - this->pose = _inertial.Pose(); - - return *this; - } + public: Inertial &operator=(const Inertial &_inertial) = default; /// \brief Equality comparison operator. /// \param[in] _inertial Inertial to copy. diff --git a/include/ignition/math/Line3.hh b/include/ignition/math/Line3.hh index f8d73b53f..7ff4c7b40 100644 --- a/include/ignition/math/Line3.hh +++ b/include/ignition/math/Line3.hh @@ -39,11 +39,7 @@ namespace ignition /// \brief Copy constructor /// \param[in] _line a line object - public: Line3(const Line3 &_line) - { - this->pts[0] = _line[0]; - this->pts[1] = _line[1]; - } + public: Line3(const Line3 &_line) = default; /// \brief Constructor. /// \param[in] _ptA Start point of the line segment @@ -373,13 +369,7 @@ namespace ignition /// \brief Assignment operator /// \param[in] _line a new value /// \return this - public: Line3 &operator=(const Line3 &_line) - { - this->pts[0] = _line[0]; - this->pts[1] = _line[1]; - - 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/ignition/math/MassMatrix3.hh b/include/ignition/math/MassMatrix3.hh index 114ec869a..25b2f68f0 100644 --- a/include/ignition/math/MassMatrix3.hh +++ b/include/ignition/math/MassMatrix3.hh @@ -61,13 +61,10 @@ namespace ignition /// \brief Copy constructor. /// \param[in] _m MassMatrix3 element to copy - public: MassMatrix3(const MassMatrix3 &_m) - : mass(_m.Mass()), Ixxyyzz(_m.DiagonalMoments()), - Ixyxzyz(_m.OffDiagonalMoments()) - {} + public: MassMatrix3(const MassMatrix3 &_m) = default; /// \brief Destructor. - public: virtual ~MassMatrix3() {} + public: ~MassMatrix3() = default; /// \brief Set the mass. /// \param[in] _m New mass value. @@ -259,13 +256,7 @@ namespace ignition /// \param[in] _massMatrix MassMatrix3 to copy. /// \return Reference to this object. public: MassMatrix3 &operator=(const MassMatrix3 &_massMatrix) - { - this->mass = _massMatrix.Mass(); - this->Ixxyyzz = _massMatrix.DiagonalMoments(); - this->Ixyxzyz = _massMatrix.OffDiagonalMoments(); - - return *this; - } + = default; /// \brief Equality comparison operator. /// \param[in] _m MassMatrix3 to copy. diff --git a/include/ignition/math/Matrix3.hh b/include/ignition/math/Matrix3.hh index 35ae47ed6..dfb0c5769 100644 --- a/include/ignition/math/Matrix3.hh +++ b/include/ignition/math/Matrix3.hh @@ -109,10 +109,7 @@ namespace ignition /// \brief Copy constructor. /// \param _m Matrix to copy - public: Matrix3(const Matrix3 &_m) - { - std::memcpy(this->data, _m.data, sizeof(this->data[0][0])*9); - } + public: Matrix3(const Matrix3 &_m) = default; /// \brief Construct a matrix3 using nine values. /// \param[in] _v00 Row 0, Col 0 value @@ -157,7 +154,7 @@ namespace ignition } /// \brief Desctructor - public: ~Matrix3() {} + public: ~Matrix3() = default; /// \brief Set a single value. /// \param[in] _row row index. _row is clamped to the range [0,2] @@ -333,11 +330,7 @@ namespace ignition /// \brief Equal operator. this = _mat /// \param _mat Matrix to copy. /// \return This matrix. - public: Matrix3 &operator=(const Matrix3 &_mat) - { - memcpy(this->data, _mat.data, sizeof(this->data[0][0])*9); - return *this; - } + public: Matrix3 &operator=(const Matrix3 &_mat) = default; /// \brief Subtraction operator. /// \param[in] _m Matrix to subtract. diff --git a/include/ignition/math/Matrix4.hh b/include/ignition/math/Matrix4.hh index 33446aa79..260342747 100644 --- a/include/ignition/math/Matrix4.hh +++ b/include/ignition/math/Matrix4.hh @@ -51,10 +51,7 @@ namespace ignition /// \brief Copy constructor /// \param _m Matrix to copy - public: Matrix4(const Matrix4 &_m) - { - memcpy(this->data, _m.data, sizeof(this->data[0][0])*16); - } + public: Matrix4(const Matrix4 &_m) = default; /// \brief Constructor /// \param[in] _v00 Row 0, Col 0 value @@ -116,7 +113,7 @@ namespace ignition } /// \brief Destructor - public: virtual ~Matrix4() {} + public: ~Matrix4() = default; /// \brief Change the values /// \param[in] _v00 Row 0, Col 0 value @@ -547,11 +544,7 @@ namespace ignition /// \brief Equal operator. this = _mat /// \param _mat Incoming matrix /// \return itself - public: Matrix4 &operator=(const Matrix4 &_mat) - { - memcpy(this->data, _mat.data, sizeof(this->data[0][0])*16); - return *this; - } + public: Matrix4 &operator=(const Matrix4 &_mat) = default; /// \brief Equal operator for 3x3 matrix /// \param _mat Incoming matrix diff --git a/include/ignition/math/OrientedBox.hh b/include/ignition/math/OrientedBox.hh index aa333802a..bdaef55f6 100644 --- a/include/ignition/math/OrientedBox.hh +++ b/include/ignition/math/OrientedBox.hh @@ -83,15 +83,10 @@ namespace ignition /// \brief Copy constructor. /// \param[in] _b OrientedBox to copy. - public: OrientedBox(const OrientedBox &_b) - : size(_b.size), pose(_b.pose), material(_b.material) - { - } + public: OrientedBox(const OrientedBox &_b) = default; /// \brief Destructor - public: virtual ~OrientedBox() - { - } + public: ~OrientedBox() = default; /// \brief Get the length along the x dimension /// \return Value of the length in the x dimension @@ -147,13 +142,7 @@ namespace ignition /// \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) - { - this->size = _b.size; - this->pose = _b.pose; - this->material = _b.material; - return *this; - } + public: OrientedBox &operator=(const OrientedBox &_b) = default; /// \brief Equality test operator /// \param[in] _b OrientedBox to test diff --git a/include/ignition/math/Plane.hh b/include/ignition/math/Plane.hh index b7ae61a7a..7c267e23e 100644 --- a/include/ignition/math/Plane.hh +++ b/include/ignition/math/Plane.hh @@ -80,12 +80,10 @@ namespace ignition /// \brief Copy constructor /// \param[in] _plane Plane to copy - public: Plane(const Plane &_plane) - : normal(_plane.normal), size(_plane.size), d(_plane.d) - {} + public: Plane(const Plane &_plane) = default; /// \brief Destructor - public: virtual ~Plane() {} + public: ~Plane() = default; /// \brief Set the plane /// \param[in] _normal The plane normal @@ -213,14 +211,7 @@ namespace ignition /// \brief Equal operator /// \param _p another plane /// \return itself - public: Plane &operator=(const Plane &_p) - { - this->normal = _p.normal; - this->size = _p.size; - this->d = _p.d; - - return *this; - } + public: Plane &operator=(const Plane &_p) = default; /// \brief Plane normal private: Vector3 normal; diff --git a/include/ignition/math/Pose3.hh b/include/ignition/math/Pose3.hh index 566b078af..78473c452 100644 --- a/include/ignition/math/Pose3.hh +++ b/include/ignition/math/Pose3.hh @@ -118,13 +118,10 @@ namespace ignition /// \brief Copy constructor. /// \param[in] _pose Pose3 to copy - public: Pose3(const Pose3 &_pose) - : p(_pose.p), q(_pose.q) - { - } + public: Pose3(const Pose3 &_pose) = default; /// \brief Destructor. - public: ~Pose3() {} + public: ~Pose3() = default; /// \brief Set the pose from a Vector3 and a Quaternion /// \param[in] _pos The position. @@ -280,12 +277,7 @@ namespace ignition /// \brief Assignment operator /// \param[in] _pose Pose3 to copy - public: Pose3 &operator=(const Pose3 &_pose) - { - this->p = _pose.p; - this->q = _pose.q; - return *this; - } + 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 diff --git a/include/ignition/math/Quaternion.hh b/include/ignition/math/Quaternion.hh index c44ebad14..d1eefd498 100644 --- a/include/ignition/math/Quaternion.hh +++ b/include/ignition/math/Quaternion.hh @@ -146,28 +146,14 @@ namespace ignition /// \brief Copy constructor. This constructor does not normalize the /// quaternion. /// \param[in] _qt Quaternion to copy - public: Quaternion(const Quaternion &_qt) - { - this->qw = _qt.qw; - this->qx = _qt.qx; - this->qy = _qt.qy; - this->qz = _qt.qz; - } + public: Quaternion(const Quaternion &_qt) = default; /// \brief Destructor - public: ~Quaternion() {} + public: ~Quaternion() = default; /// \brief Assignment operator /// \param[in] _qt Quaternion to copy - public: Quaternion &operator=(const Quaternion &_qt) - { - this->qw = _qt.qw; - this->qx = _qt.qx; - this->qy = _qt.qy; - this->qz = _qt.qz; - - return *this; - } + public: Quaternion &operator=(const Quaternion &_qt) = default; /// \brief Invert the quaternion. The quaternion is first normalized, /// then inverted. diff --git a/include/ignition/math/Stopwatch.hh b/include/ignition/math/Stopwatch.hh index f469672f5..2e302d2fc 100644 --- a/include/ignition/math/Stopwatch.hh +++ b/include/ignition/math/Stopwatch.hh @@ -72,7 +72,7 @@ namespace ignition public: Stopwatch(Stopwatch &&_watch) noexcept; /// \brief Destructor. - public: virtual ~Stopwatch(); + public: ~Stopwatch(); /// \brief Start the stopwatch. /// \param[in] _reset If true the stopwatch is reset first. diff --git a/include/ignition/math/Vector2.hh b/include/ignition/math/Vector2.hh index 3d297b424..ae38dc889 100644 --- a/include/ignition/math/Vector2.hh +++ b/include/ignition/math/Vector2.hh @@ -58,14 +58,10 @@ namespace ignition /// \brief Copy constructor /// \param[in] _v the value - public: Vector2(const Vector2 &_v) - { - this->data[0] = _v[0]; - this->data[1] = _v[1]; - } + public: constexpr Vector2(const Vector2 &_v) = default; /// \brief Destructor - public: virtual ~Vector2() {} + public: ~Vector2() = default; /// \brief Return the sum of the values /// \return the sum @@ -222,13 +218,7 @@ namespace ignition /// \brief Assignment operator /// \param[in] _v a value for x and y element /// \return this - public: Vector2 &operator=(const Vector2 &_v) - { - this->data[0] = _v[0]; - this->data[1] = _v[1]; - - return *this; - } + public: Vector2 &operator=(const Vector2 &_v) = default; /// \brief Assignment operator /// \param[in] _v the value for x and y element diff --git a/include/ignition/math/Vector3.hh b/include/ignition/math/Vector3.hh index eafa60307..39bbb08d4 100644 --- a/include/ignition/math/Vector3.hh +++ b/include/ignition/math/Vector3.hh @@ -75,15 +75,10 @@ namespace ignition /// \brief Copy constructor /// \param[in] _v a vector - public: Vector3(const Vector3 &_v) - { - this->data[0] = _v[0]; - this->data[1] = _v[1]; - this->data[2] = _v[2]; - } + public: Vector3(const Vector3 &_v) = default; /// \brief Destructor - public: virtual ~Vector3() {} + public: ~Vector3() = default; /// \brief Return the sum of the values /// \return the sum @@ -330,14 +325,7 @@ namespace ignition /// \brief Assignment operator /// \param[in] _v a new value /// \return this - public: Vector3 &operator=(const Vector3 &_v) - { - this->data[0] = _v[0]; - this->data[1] = _v[1]; - this->data[2] = _v[2]; - - return *this; - } + public: Vector3 &operator=(const Vector3 &_v) = default; /// \brief Assignment operator /// \param[in] _v assigned to all elements diff --git a/include/ignition/math/Vector4.hh b/include/ignition/math/Vector4.hh index b1484cc6e..bfb39ddab 100644 --- a/include/ignition/math/Vector4.hh +++ b/include/ignition/math/Vector4.hh @@ -62,16 +62,10 @@ namespace ignition /// \brief Copy constructor /// \param[in] _v vector - public: Vector4(const Vector4 &_v) - { - this->data[0] = _v[0]; - this->data[1] = _v[1]; - this->data[2] = _v[2]; - this->data[3] = _v[3]; - } + public: Vector4(const Vector4 &_v) = default; /// \brief Destructor - public: virtual ~Vector4() {} + public: ~Vector4() = default; /// \brief Calc distance to the given point /// \param[in] _pt the point @@ -264,15 +258,7 @@ namespace ignition /// \brief Assignment operator /// \param[in] _v the vector /// \return a reference to this vector - public: Vector4 &operator=(const Vector4 &_v) - { - this->data[0] = _v[0]; - this->data[1] = _v[1]; - this->data[2] = _v[2]; - this->data[3] = _v[3]; - - return *this; - } + public: Vector4 &operator=(const Vector4 &_v) = default; /// \brief Assignment operator /// \param[in] _value diff --git a/src/Color.cc b/src/Color.cc index f70b9d69a..e9ffec67f 100644 --- a/src/Color.cc +++ b/src/Color.cc @@ -44,16 +44,10 @@ Color::Color(const float _r, const float _g, const float _b, const float _a) } ////////////////////////////////////////////////// -Color::Color(const Color &_pt) -: r(_pt.r), g(_pt.g), b(_pt.b), a(_pt.a) -{ - this->Clamp(); -} +Color::Color(const Color &_pt) = default; ////////////////////////////////////////////////// -Color::~Color() -{ -} +Color::~Color() = default; ////////////////////////////////////////////////// void Color::Reset() diff --git a/src/PID.cc b/src/PID.cc index c1fad8725..37376635e 100644 --- a/src/PID.cc +++ b/src/PID.cc @@ -51,27 +51,7 @@ void PID::Init(const double _p, const double _i, const double _d, } ///////////////////////////////////////////////// -PID &PID::operator=(const PID &_p) -{ - if (this == &_p) - return *this; - - this->pGain = _p.pGain; - this->iGain = _p.iGain; - this->dGain = _p.dGain; - this->iMax = _p.iMax; - this->iMin = _p.iMin; - this->cmdMax = _p.cmdMax; - this->cmdMin = _p.cmdMin; - this->cmdOffset = _p.cmdOffset; - this->pErrLast = _p.pErrLast; - this->pErr = _p.pErr; - this->iErr = _p.iErr; - this->dErr = _p.dErr; - this->cmd = _p.cmd; - - return *this; -} +PID &PID::operator=(const PID &_p) = default; ///////////////////////////////////////////////// void PID::SetPGain(const double _p)