Skip to content

Commit

Permalink
Remove APIs deprecated in gz-math7
Browse files Browse the repository at this point in the history
Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters committed Jul 1, 2024
1 parent be4b1ab commit 337df73
Show file tree
Hide file tree
Showing 12 changed files with 2 additions and 371 deletions.
2 changes: 2 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,8 @@ release will remove the deprecated code.
header files, the `ignition::` namespaces, and `IGN_*` and `IGNITION_*`
macros.

1. Deprecated functionality from version 7 has been removed.

### Deprecations

1. **Stopwatch.hh**
Expand Down
10 changes: 0 additions & 10 deletions include/gz/math/Angle.hh
Original file line number Diff line number Diff line change
Expand Up @@ -96,20 +96,10 @@ namespace gz
{
}

/// \brief Set the value from an angle in radians.
/// \param[in] _radian Radian value.
/// \deprecated Use void SetRadian(double)
public: void GZ_DEPRECATED(7) Radian(double _radian);

/// \brief Set the value from an angle in radians.
/// \param[in] _radian Radian value.
public: void SetRadian(double _radian);

/// \brief Set the value from an angle in degrees
/// \param[in] _degree Degree value
/// \deprecated Use void SetDegree(double)
public: void GZ_DEPRECATED(7) Degree(double _degree);

/// \brief Set the value from an angle in degrees
/// \param[in] _degree Degree value
public: void SetDegree(double _degree);
Expand Down
45 changes: 0 additions & 45 deletions include/gz/math/Matrix3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -185,19 +185,6 @@ namespace gz
this->data[2][2] = _v22;
}

/// \brief Set the matrix from three axis (1 per column).
/// \param[in] _xAxis The x axis, the first column of the matrix.
/// \param[in] _yAxis The y axis, the second column of the matrix.
/// \param[in] _zAxis The z axis, the third column of the matrix.
/// \deprecated Use SetAxes(const Vector3<T> &, const Vector3<T> &,
/// const Vector3<T> &,)
public: void GZ_DEPRECATED(7) Axes(const Vector3<T> &_xAxis,
const Vector3<T> &_yAxis,
const Vector3<T> &_zAxis)
{
this->SetAxes(_xAxis, _yAxis, _zAxis);
}

/// \brief Set the matrix from three axis (1 per column).
/// \param[in] _xAxis The x axis, the first column of the matrix.
/// \param[in] _yAxis The y axis, the second column of the matrix.
Expand All @@ -211,15 +198,6 @@ namespace gz
this->SetCol(2, _zAxis);
}

/// \brief Set as a rotation matrix from an axis and angle.
/// \param[in] _axis the axis
/// \param[in] _angle ccw rotation around the axis in radians
/// \deprecated Use SetFromAxisAngle(const Vector3<T> &, T)
public: void GZ_DEPRECATED(7) Axis(const Vector3<T> &_axis, T _angle)
{
this->SetFromAxisAngle(_axis, _angle);
}

/// \brief Set as a rotation matrix from an axis and angle.
/// \param[in] _axis the axis
/// \param[in] _angle ccw rotation around the axis in radians
Expand All @@ -242,19 +220,6 @@ namespace gz
this->data[2][2] = _axis.Z()*_axis.Z()*C + c;
}

/// \brief Set as a rotation matrix to represent rotation from
/// vector _v1 to vector _v2, so that
/// _v2.Normalize() == this * _v1.Normalize() holds.
///
/// \param[in] _v1 The first vector
/// \param[in] _v2 The second vector
/// \deprecated Use SetFrom2Axes(const Vector3<T> &, const Vector3<T> &)
public: void GZ_DEPRECATED(7) From2Axes(
const Vector3<T> &_v1, const Vector3<T> &_v2)
{
this->SetFrom2Axes(_v1, _v2);
}

/// \brief Set as a rotation matrix to represent rotation from
/// vector _v1 to vector _v2, so that
/// _v2.Normalize() == this * _v1.Normalize() holds.
Expand Down Expand Up @@ -298,16 +263,6 @@ namespace gz
this->SetFromAxisAngle(cross, acos(dot));
}

/// \brief Set a column.
/// \param[in] _c The colum index [0, 1, 2]. _col is clamped to the
/// range [0, 2].
/// \param[in] _v The value to set in each row of the column.
/// \deprecated Use SetCol(unsigned int _c, const Vector3<T> &_v)
public: void GZ_DEPRECATED(7) Col(unsigned int _c, const Vector3<T> &_v)
{
this->SetCol(_c, _v);
}

/// \brief Set a column.
/// \param[in] _c The colum index [0, 1, 2]. _col is clamped to the
/// range [0, 2].
Expand Down
63 changes: 0 additions & 63 deletions include/gz/math/Pose3.hh
Original file line number Diff line number Diff line change
Expand Up @@ -177,69 +177,6 @@ namespace gz
return Pose3<T>(inv * (this->p*-1), inv);
}

/// \brief Addition operator.
/// A is the transform from O to P specified in frame O
/// B is the transform from P to Q specified in frame P
/// then, B + A is the transform from O to Q specified in frame O
/// \param[in] _pose Pose3<T> to add to this pose.
/// \return The resulting pose.
public: GZ_DEPRECATED(7) Pose3<T> operator+(const Pose3<T> &_pose) const
{
Pose3<T> result;

result.p = this->CoordPositionAdd(_pose);
result.q = this->CoordRotationAdd(_pose.q);

return result;
}

/// \brief Addition assignment operator.
/// \param[in] _pose Pose3<T> to add to this pose.
/// \sa operator+(const Pose3<T> &_pose) const.
/// \return The resulting pose.
public: GZ_DEPRECATED(7) const Pose3<T> &
operator+=(const Pose3<T> &_pose)
{
this->p = this->CoordPositionAdd(_pose);
this->q = this->CoordRotationAdd(_pose.q);

return *this;
}

/// \brief Negation operator.
/// A is the transform from O to P in frame O
/// then -A is transform from P to O specified in frame P
/// \return The resulting pose.
public: GZ_DEPRECATED(7) Pose3<T> operator-() const
{
return this->Inverse();
}

/// \brief Subtraction operator.
/// A is the transform from O to P in frame O
/// B is the transform from O to Q in frame O
/// B - A is the transform from P to Q in frame P
/// \param[in] _pose Pose3<T> to subtract from this one.
/// \return The resulting pose.
public: GZ_DEPRECATED(7) Pose3<T> operator-(const Pose3<T> &_pose) const
{
return Pose3<T>(this->CoordPositionSub(_pose),
this->CoordRotationSub(_pose.q));
}

/// \brief Subtraction assignment operator.
/// \param[in] _pose Pose3<T> to subtract from this one
/// \sa operator-(const Pose3<T> &_pose) const.
/// \return The resulting pose
public: GZ_DEPRECATED(7) const Pose3<T> &
operator-=(const Pose3<T> &_pose)
{
this->p = this->CoordPositionSub(_pose);
this->q = this->CoordRotationSub(_pose.q);

return *this;
}

/// \brief Equality operator.
/// \param[in] _pose Pose3<T> for comparison.
/// \return True if this pose is equal to the given pose.
Expand Down
111 changes: 0 additions & 111 deletions include/gz/math/Quaternion.hh
Original file line number Diff line number Diff line change
Expand Up @@ -295,17 +295,6 @@ namespace gz
return result;
}

/// \brief Set the quaternion from an axis and angle
/// \param[in] _ax X axis
/// \param[in] _ay Y axis
/// \param[in] _az Z axis
/// \param[in] _aa Angle in radians
/// \deprecated Use SetFromAxisAngle(T, T, T, T)
public: void GZ_DEPRECATED(7) Axis(T _ax, T _ay, T _az, T _aa)
{
this->SetFromAxisAngle(_ax, _ay, _az, _aa);
}

/// \brief Set the quaternion from an axis and angle.
/// \param[in] _ax X axis
/// \param[in] _ay Y axis
Expand Down Expand Up @@ -337,15 +326,6 @@ namespace gz
this->Normalize();
}

/// \brief Set the quaternion from an axis and angle
/// \param[in] _axis Axis
/// \param[in] _a Angle in radians
/// \deprecated Use SetFromAxisAngle(const Vector3<T> &_axis, T _a)
public: void GZ_DEPRECATED(7) Axis(const Vector3<T> &_axis, T _a)
{
this->SetFromAxisAngle(_axis, _a);
}

/// \brief Set the quaternion from an axis and angle
/// \param[in] _axis Axis
/// \param[in] _a Angle in radians
Expand All @@ -367,17 +347,6 @@ namespace gz
this->qz = _z;
}

/// \brief Set the quaternion from Euler angles. The order of operations
/// is roll, pitch, yaw around a fixed body frame axis
/// (the original frame of the object before rotation is applied).
/// Roll is a rotation about x, pitch is about y, yaw is about z.
/// \param[in] _vec Euler angle
/// \deprecated Use SetFromEuler(const Vector3<T> &)
public: void GZ_DEPRECATED(7) Euler(const Vector3<T> &_vec)
{
this->SetFromEuler(_vec);
}

/// \brief Set the quaternion from Euler angles. The order of operations
/// is roll, pitch, yaw around a fixed body frame axis
/// (the original frame of the object before rotation is applied).
Expand All @@ -388,16 +357,6 @@ namespace gz
this->SetFromEuler(_vec.X(), _vec.Y(), _vec.Z());
}

/// \brief Set the quaternion from Euler angles.
/// \param[in] _roll Roll angle (radians).
/// \param[in] _pitch Pitch angle (radians).
/// \param[in] _yaw Yaw angle (radians).
/// \deprecated Use SetFromEuler(T, T, T)
public: void GZ_DEPRECATED(7) Euler(T _roll, T _pitch, T _yaw)
{
this->SetFromEuler(_roll, _pitch, _yaw);
}

/// \brief Set the quaternion from Euler angles.
/// \param[in] _roll Roll angle in radians.
/// \param[in] _pitch Pitch angle in radians.
Expand Down Expand Up @@ -531,15 +490,6 @@ namespace gz
return this->Euler().Z();
}

/// \brief Return rotation as axis and angle
/// \param[out] _axis rotation axis
/// \param[out] _angle ccw angle in radians
/// \deprecated Use AxisAngle(Vector3<T> &_axis, T &_angle) const
public: void GZ_DEPRECATED(7) ToAxis(Vector3<T> &_axis, T &_angle) const
{
this->AxisAngle(_axis, _angle);
}

/// \brief Convert this quaternion to an axis and angle.
/// \param[out] _axis Rotation axis.
/// \param[out] _angle CCW angle in radians.
Expand All @@ -559,19 +509,6 @@ namespace gz
}
}

/// \brief Set from a rotation matrix.
/// \param[in] _mat rotation matrix (must be orthogonal, the function
/// doesn't check it)
///
/// Implementation inspired by
/// http://www.euclideanspace.com/maths/geometry/rotations/
/// conversions/matrixToQuaternion/
/// \deprecated Use SetFromMatrix(const Matrix3<T>&)
public: void GZ_DEPRECATED(7) Matrix(const Matrix3<T> &_mat)
{
this->SetFromMatrix(_mat);
}

/// \brief Set from a rotation matrix.
/// \param[in] _mat Rotation matrix (must be orthogonal, the function
/// doesn't check it).
Expand Down Expand Up @@ -616,22 +553,6 @@ namespace gz
}
}

/// \brief Set this quaternion to represent rotation from
/// vector _v1 to vector _v2, so that
/// _v2.Normalize() == this * _v1.Normalize() holds.
///
/// \param[in] _v1 The first vector.
/// \param[in] _v2 The second vector.
///
/// Implementation inspired by
/// http://stackoverflow.com/a/11741520/1076564
/// \deprecated Use SetFrom2Axes(const Vector3<T> &, const Vector3<T> &)
public: void GZ_DEPRECATED(7) From2Axes(
const Vector3<T> &_v1, const Vector3<T> &_v2)
{
this->SetFrom2Axes(_v1, _v2);
}

/// \brief Set this quaternion to represent rotation from
/// vector _v1 to vector _v2, so that
/// _v2.Normalize() == this * _v1.Normalize() holds.
Expand Down Expand Up @@ -1131,29 +1052,13 @@ namespace gz
return this->qz;
}

/// \brief Set the x component.
/// \param[in] _v The new value for the x quaternion component.
/// \deprecated Use SetX(T)
public: inline void GZ_DEPRECATED(7) X(T _v)
{
this->SetX(_v);
}

/// \brief Set the x component.
/// \param[in] _v The new value for the x quaternion component.
public: inline void SetX(T _v)
{
this->qx = _v;
}

/// \brief Set the y component.
/// \param[in] _v The new value for the y quaternion component.
/// \deprecated Use SetY(T)
public: inline void GZ_DEPRECATED(7) Y(T _v)
{
this->SetY(_v);
}

/// \brief Set the y component.
/// \param[in] _v The new value for the y quaternion component.
public: inline void SetY(T _v)
Expand All @@ -1162,29 +1067,13 @@ namespace gz
}


/// \brief Set the z component.
/// \param[in] _v The new value for the z quaternion component.
/// \deprecated Use SetZ(T)
public: inline void GZ_DEPRECATED(7) Z(T _v)
{
this->SetZ(_v);
}

/// \brief Set the z component.
/// \param[in] _v The new value for the z quaternion component.
public: inline void SetZ(T _v)
{
this->qz = _v;
}

/// \brief Set the w component.
/// \param[in] _v The new value for the w quaternion component.
/// \deprecated Use SetW(T)
public: inline void GZ_DEPRECATED(7) W(T _v)
{
this->SetW(_v);
}

/// \brief Set the w component.
/// \param[in] _v The new value for the w quaternion component.
public: inline void SetW(T _v)
Expand Down
16 changes: 0 additions & 16 deletions include/gz/math/SphericalCoordinates.hh
Original file line number Diff line number Diff line change
Expand Up @@ -144,22 +144,6 @@ namespace gz
/// \return Type as string
public: static std::string Convert(SurfaceType _type);

/// \brief Get the distance between two points expressed in geographic
/// latitude and longitude. It assumes that both points are at sea level.
/// Example: _latA = 38.0016667 and _lonA = -123.0016667) represents
/// the point with latitude 38d 0'6.00"N and longitude 123d 0'6.00"W.
/// \param[in] _latA Latitude of point A.
/// \param[in] _lonA Longitude of point A.
/// \param[in] _latB Latitude of point B.
/// \param[in] _lonB Longitude of point B.
/// \return Distance in meters.
/// \deprecated Use DistanceWGS84 instead.
public: GZ_DEPRECATED(7) static double Distance(
const gz::math::Angle &_latA,
const gz::math::Angle &_lonA,
const gz::math::Angle &_latB,
const gz::math::Angle &_lonB);

/// \brief Get the distance between two points expressed in geographic
/// latitude and longitude. It assumes that both points are at sea level.
/// Example: _latA = 38.0016667 and _lonA = -123.0016667) represents
Expand Down
Loading

0 comments on commit 337df73

Please sign in to comment.