Skip to content

Commit

Permalink
Tidy up copy, copy-assign, and destructors (#293)
Browse files Browse the repository at this point in the history
Remove virtual from destructors of copyable classes.  A class that is
copyable or copy-assignable should never be virtual, because any subclass
will be subject to the slicing problem.

Use '= default' anytime we just want the default implementation.  Writing
out the list of member fields by hand is error-prone.

Signed-off-by: Jeremy Nimmer <[email protected]>
  • Loading branch information
jwnimmer-tri authored Nov 30, 2021
1 parent 797f67f commit 1366e82
Show file tree
Hide file tree
Showing 20 changed files with 47 additions and 189 deletions.
3 changes: 3 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
2 changes: 1 addition & 1 deletion include/ignition/math/AxisAlignedBox.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
4 changes: 2 additions & 2 deletions include/ignition/math/Box.hh
Original file line number Diff line number Diff line change
Expand Up @@ -84,10 +84,10 @@ namespace ignition

/// \brief Copy Constructor.
/// \param[in] _b Box to copy.
public: Box(const Box<Precision> &_b);
public: Box(const Box<Precision> &_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.
Expand Down
2 changes: 1 addition & 1 deletion include/ignition/math/Color.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
2 changes: 1 addition & 1 deletion include/ignition/math/Frustum.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
14 changes: 3 additions & 11 deletions include/ignition/math/Inertial.hh
Original file line number Diff line number Diff line change
Expand Up @@ -64,12 +64,10 @@ namespace ignition

/// \brief Copy constructor.
/// \param[in] _inertial Inertial element to copy
public: Inertial(const Inertial<T> &_inertial)
: massMatrix(_inertial.MassMatrix()), pose(_inertial.Pose())
{}
public: Inertial(const Inertial<T> &_inertial) = default;

/// \brief Destructor.
public: virtual ~Inertial() {}
public: ~Inertial() = default;

/// \brief Set the mass and inertia matrix.
///
Expand Down Expand Up @@ -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<T> &_inertial)
{
this->massMatrix = _inertial.MassMatrix();
this->pose = _inertial.Pose();

return *this;
}
public: Inertial &operator=(const Inertial<T> &_inertial) = default;

/// \brief Equality comparison operator.
/// \param[in] _inertial Inertial to copy.
Expand Down
14 changes: 2 additions & 12 deletions include/ignition/math/Line3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,7 @@ namespace ignition

/// \brief Copy constructor
/// \param[in] _line a line object
public: Line3(const Line3<T> &_line)
{
this->pts[0] = _line[0];
this->pts[1] = _line[1];
}
public: Line3(const Line3<T> &_line) = default;

/// \brief Constructor.
/// \param[in] _ptA Start point of the line segment
Expand Down Expand Up @@ -373,13 +369,7 @@ namespace ignition
/// \brief Assignment operator
/// \param[in] _line a new value
/// \return this
public: Line3 &operator=(const Line3<T> &_line)
{
this->pts[0] = _line[0];
this->pts[1] = _line[1];

return *this;
}
public: Line3 &operator=(const Line3<T> &_line) = default;

/// \brief Vector for storing the start and end points of the line
private: math::Vector3<T> pts[2];
Expand Down
15 changes: 3 additions & 12 deletions include/ignition/math/MassMatrix3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -61,13 +61,10 @@ namespace ignition

/// \brief Copy constructor.
/// \param[in] _m MassMatrix3 element to copy
public: MassMatrix3(const MassMatrix3<T> &_m)
: mass(_m.Mass()), Ixxyyzz(_m.DiagonalMoments()),
Ixyxzyz(_m.OffDiagonalMoments())
{}
public: MassMatrix3(const MassMatrix3<T> &_m) = default;

/// \brief Destructor.
public: virtual ~MassMatrix3() {}
public: ~MassMatrix3() = default;

/// \brief Set the mass.
/// \param[in] _m New mass value.
Expand Down Expand Up @@ -259,13 +256,7 @@ namespace ignition
/// \param[in] _massMatrix MassMatrix3 to copy.
/// \return Reference to this object.
public: MassMatrix3 &operator=(const MassMatrix3<T> &_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.
Expand Down
13 changes: 3 additions & 10 deletions include/ignition/math/Matrix3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -109,10 +109,7 @@ namespace ignition

/// \brief Copy constructor.
/// \param _m Matrix to copy
public: Matrix3(const Matrix3<T> &_m)
{
std::memcpy(this->data, _m.data, sizeof(this->data[0][0])*9);
}
public: Matrix3(const Matrix3<T> &_m) = default;

/// \brief Construct a matrix3 using nine values.
/// \param[in] _v00 Row 0, Col 0 value
Expand Down Expand Up @@ -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]
Expand Down Expand Up @@ -333,11 +330,7 @@ namespace ignition
/// \brief Equal operator. this = _mat
/// \param _mat Matrix to copy.
/// \return This matrix.
public: Matrix3<T> &operator=(const Matrix3<T> &_mat)
{
memcpy(this->data, _mat.data, sizeof(this->data[0][0])*9);
return *this;
}
public: Matrix3<T> &operator=(const Matrix3<T> &_mat) = default;

/// \brief Subtraction operator.
/// \param[in] _m Matrix to subtract.
Expand Down
13 changes: 3 additions & 10 deletions include/ignition/math/Matrix4.hh
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,7 @@ namespace ignition

/// \brief Copy constructor
/// \param _m Matrix to copy
public: Matrix4(const Matrix4<T> &_m)
{
memcpy(this->data, _m.data, sizeof(this->data[0][0])*16);
}
public: Matrix4(const Matrix4<T> &_m) = default;

/// \brief Constructor
/// \param[in] _v00 Row 0, Col 0 value
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -547,11 +544,7 @@ namespace ignition
/// \brief Equal operator. this = _mat
/// \param _mat Incoming matrix
/// \return itself
public: Matrix4<T> &operator=(const Matrix4<T> &_mat)
{
memcpy(this->data, _mat.data, sizeof(this->data[0][0])*16);
return *this;
}
public: Matrix4<T> &operator=(const Matrix4<T> &_mat) = default;

/// \brief Equal operator for 3x3 matrix
/// \param _mat Incoming matrix
Expand Down
17 changes: 3 additions & 14 deletions include/ignition/math/OrientedBox.hh
Original file line number Diff line number Diff line change
Expand Up @@ -83,15 +83,10 @@ namespace ignition

/// \brief Copy constructor.
/// \param[in] _b OrientedBox to copy.
public: OrientedBox(const OrientedBox<T> &_b)
: size(_b.size), pose(_b.pose), material(_b.material)
{
}
public: OrientedBox(const OrientedBox<T> &_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
Expand Down Expand Up @@ -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<T> &_b)
{
this->size = _b.size;
this->pose = _b.pose;
this->material = _b.material;
return *this;
}
public: OrientedBox &operator=(const OrientedBox<T> &_b) = default;

/// \brief Equality test operator
/// \param[in] _b OrientedBox to test
Expand Down
15 changes: 3 additions & 12 deletions include/ignition/math/Plane.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -213,14 +211,7 @@ namespace ignition
/// \brief Equal operator
/// \param _p another plane
/// \return itself
public: Plane<T> &operator=(const Plane<T> &_p)
{
this->normal = _p.normal;
this->size = _p.size;
this->d = _p.d;

return *this;
}
public: Plane<T> &operator=(const Plane<T> &_p) = default;

/// \brief Plane normal
private: Vector3<T> normal;
Expand Down
14 changes: 3 additions & 11 deletions include/ignition/math/Pose3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -118,13 +118,10 @@ namespace ignition

/// \brief Copy constructor.
/// \param[in] _pose Pose3<T> to copy
public: Pose3(const Pose3<T> &_pose)
: p(_pose.p), q(_pose.q)
{
}
public: Pose3(const Pose3<T> &_pose) = default;

/// \brief Destructor.
public: ~Pose3() {}
public: ~Pose3() = default;

/// \brief Set the pose from a Vector3<T> and a Quaternion<T>
/// \param[in] _pos The position.
Expand Down Expand Up @@ -280,12 +277,7 @@ namespace ignition

/// \brief Assignment operator
/// \param[in] _pose Pose3<T> to copy
public: Pose3<T> &operator=(const Pose3<T> &_pose)
{
this->p = _pose.p;
this->q = _pose.q;
return *this;
}
public: Pose3<T> &operator=(const Pose3<T> &_pose) = default;

/// \brief Add one point to a vector: result = this + pos.
/// \param[in] _pos Position to add to this pose
Expand Down
20 changes: 3 additions & 17 deletions include/ignition/math/Quaternion.hh
Original file line number Diff line number Diff line change
Expand Up @@ -146,28 +146,14 @@ namespace ignition
/// \brief Copy constructor. This constructor does not normalize the
/// quaternion.
/// \param[in] _qt Quaternion<T> to copy
public: Quaternion(const Quaternion<T> &_qt)
{
this->qw = _qt.qw;
this->qx = _qt.qx;
this->qy = _qt.qy;
this->qz = _qt.qz;
}
public: Quaternion(const Quaternion<T> &_qt) = default;

/// \brief Destructor
public: ~Quaternion() {}
public: ~Quaternion() = default;

/// \brief Assignment operator
/// \param[in] _qt Quaternion<T> to copy
public: Quaternion<T> &operator=(const Quaternion<T> &_qt)
{
this->qw = _qt.qw;
this->qx = _qt.qx;
this->qy = _qt.qy;
this->qz = _qt.qz;

return *this;
}
public: Quaternion<T> &operator=(const Quaternion<T> &_qt) = default;

/// \brief Invert the quaternion. The quaternion is first normalized,
/// then inverted.
Expand Down
2 changes: 1 addition & 1 deletion include/ignition/math/Stopwatch.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
16 changes: 3 additions & 13 deletions include/ignition/math/Vector2.hh
Original file line number Diff line number Diff line change
Expand Up @@ -58,14 +58,10 @@ namespace ignition

/// \brief Copy constructor
/// \param[in] _v the value
public: Vector2(const Vector2<T> &_v)
{
this->data[0] = _v[0];
this->data[1] = _v[1];
}
public: constexpr Vector2(const Vector2<T> &_v) = default;

/// \brief Destructor
public: virtual ~Vector2() {}
public: ~Vector2() = default;

/// \brief Return the sum of the values
/// \return the sum
Expand Down Expand Up @@ -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
Expand Down
Loading

0 comments on commit 1366e82

Please sign in to comment.