Skip to content

Commit

Permalink
Remove deprecations: tock (#653)
Browse files Browse the repository at this point in the history
* Remove deprecations: tock

Signed-off-by: Carlos Agüero <caguero@openrobotics.org>
  • Loading branch information
caguero authored Dec 5, 2024
1 parent 1d5916d commit 6a146ad
Show file tree
Hide file tree
Showing 10 changed files with 44 additions and 1,534 deletions.
37 changes: 37 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,43 @@ Deprecated code produces compile-time warnings. These warning serve as
notification to users that their code should be upgraded. The next major
release will remove the deprecated code.

## Gazebo Math 8.X to 9.X

1. **SphericalCoordinates.hh**
Remove `math::SphericalCoordinates::LOCAL2` and related functions.
See https://github.com/gazebosim/gz-math/pull/235 . The current behavior
converting `LOCAL` to `GLOBAL` should be correct now, unrolling the previous
incoherent result, only present to preserve behavior.

+ Removed: `gz::math::Vector3d SphericalFromLocalPosition(
const gz::math::Vector3d &_xyz) const`
+ Removed: `gz::math::Vector3d GlobalFromLocalVelocity(
const gz::math::Vector3d &_xyz) const`
+ Removed: `gz::math::Vector3d LocalFromSphericalPosition(
const gz::math::Vector3d &_latLonEle) const`
+ Removed: `gz::math::Vector3d LocalFromGlobalVelocity(
const gz::math::Vector3d &_xyz) const`
+ Removed: `gz::math::Vector3d
PositionTransform(const gz::math::Vector3d &_pos,
const CoordinateType &_in, const CoordinateType &_out) const`
+ Removed: `gz::math::Vector3d VelocityTransform(
const gz::math::Vector3d &_vel,
const CoordinateType &_in, const CoordinateType &_out) const`

1. **Stopwatch.hh**
+ The `math::clock` type alias has been removed. Please use the underlying
type (`std::chrono::steady_clock`) directly.

1. **graph/Vertex.hh**
+ The `Vertex::NullVertex` static member has been removed. Please use
`Vertex::NullVertex()` instead.
E.g.: https://github.com/gazebosim/gz-math/pull/606/files#diff-0c0220a7e72be70337975433eeddc3f5e072ade5cd80dfb1ac03da233c39c983L153-R153

1. **graph/Edge.hh**
+ The `Edge::NullEdge` static member has been removed. Please use
`Vertex::NullEdge()` instead.
E.g.: https://github.com/gazebosim/gz-math/pull/606/files#diff-0c0220a7e72be70337975433eeddc3f5e072ade5cd80dfb1ac03da233c39c983L222-R222

## Gazebo Math 7.X to 8.X

### Breaking Changes
Expand Down
102 changes: 0 additions & 102 deletions include/gz/math/SphericalCoordinates.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,6 @@
#include <gz/math/config.hh>
#include <gz/utils/ImplPtr.hh>

// MSVC doesn't like deprecating enum values with function macros
#if _MSC_VER
#define GZ_LOCAL2_DEPRECATED [[deprecated]]
#else
#define GZ_LOCAL2_DEPRECATED GZ_DEPRECATED(8)
#endif

namespace gz::math
{
// Inline bracket to help doxygen filtering.
Expand Down Expand Up @@ -74,12 +67,6 @@ namespace gz::math

/// \brief Heading-adjusted tangent plane (X, Y, Z)
LOCAL = 4,

/// \brief Heading-adjusted tangent plane (X, Y, Z)
/// \deprecated The computation bugs for LOCAL have been fixed
/// in Gazebo Ionic (8) so the temporary LOCAL2 type
/// is no more needed.
LOCAL2 GZ_LOCAL2_DEPRECATED = 5
};

/// \brief Constructor.
Expand Down Expand Up @@ -111,21 +98,6 @@ namespace gz::math
const double _elevation,
const gz::math::Angle &_heading);

/// \brief Convert a Cartesian position vector to geodetic coordinates.
/// This performs a `PositionTransform` from LOCAL to SPHERICAL.
///
/// \deprecated There's a known bug with this computation that can't be
/// fixed until Gazebo 8 to avoid behaviour changes.
/// Call `SphericalFromLocalPosition(CoordinateVector3)` for correct
/// results.
///
/// \param[in] _xyz Cartesian position vector in the heading-adjusted
/// world frame.
/// \return Cooordinates: geodetic latitude (deg), longitude (deg),
/// altitude above sea level (m).
public: GZ_DEPRECATED(8) gz::math::Vector3d SphericalFromLocalPosition(
const gz::math::Vector3d &_xyz) const;

/// \brief Convert a Cartesian position vector to geodetic coordinates.
/// This performs a `PositionTransform` from LOCAL to SPHERICAL.
///
Expand All @@ -136,21 +108,6 @@ namespace gz::math
public: std::optional<math::CoordinateVector3> SphericalFromLocalPosition(
const gz::math::CoordinateVector3 &_xyz) const;

/// \brief Convert a Cartesian velocity vector in the local frame
/// to a global Cartesian frame with components East, North, Up.
/// This is a wrapper around `VelocityTransform(_xyz, LOCAL, GLOBAL)`
///
/// \deprecated There's a known bug with this computation that can't be
/// fixed until Gazebo 8 to avoid behaviour changes.
/// Call `GlobalFromLocalVelocity(CoordinateVector3)` for correct
/// results.
///
/// \param[in] _xyz Cartesian velocity vector in the heading-adjusted
/// world frame.
/// \return Rotated vector with components (x,y,z): (East, North, Up).
public: GZ_DEPRECATED(8) gz::math::Vector3d GlobalFromLocalVelocity(
const gz::math::Vector3d &_xyz) const;

/// \brief Convert a Cartesian velocity vector in the local frame
/// to a global Cartesian frame with components East, North, Up.
/// This is a wrapper around `VelocityTransform(_xyz, LOCAL, GLOBAL)`
Expand Down Expand Up @@ -192,8 +149,6 @@ namespace gz::math
/// 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.
/// This is different from the deprecated static Distance() method as it
/// takes into account the set surface's radius.
/// \param[in] _latA Latitude of point A.
/// \param[in] _lonA Longitude of point A.
/// \param[in] _latB Latitude of point B.
Expand Down Expand Up @@ -273,15 +228,6 @@ namespace gz::math
/// \param[in] _angle Heading offset for the frame.
public: void SetHeadingOffset(const gz::math::Angle &_angle);

/// \brief Convert a geodetic position vector to Cartesian coordinates.
/// This performs a `PositionTransform` from SPHERICAL to LOCAL.
/// \deprecated Use `LocalFromSphericalPosition(CoordinateVector3)` instead.
/// \param[in] _latLonEle Geodetic position in the planetary frame of
/// reference. X: latitude (deg), Y: longitude (deg), X: altitude.
/// \return Cartesian position vector in the heading-adjusted world frame.
public: GZ_DEPRECATED(8) gz::math::Vector3d LocalFromSphericalPosition(
const gz::math::Vector3d &_latLonEle) const;

/// \brief Convert a geodetic position vector to Cartesian coordinates.
/// This performs a `PositionTransform` from SPHERICAL to LOCAL.
/// \param[in] _latLonEle Geodetic position in the planetary frame of
Expand All @@ -290,15 +236,6 @@ namespace gz::math
public: std::optional<math::CoordinateVector3> LocalFromSphericalPosition(
const gz::math::CoordinateVector3 &_latLonEle) const;

/// \brief Convert a Cartesian velocity vector with components East,
/// North, Up to a local cartesian frame vector XYZ.
/// This is a wrapper around `VelocityTransform(_xyz, GLOBAL, LOCAL)`
/// \deprecated Use `LocalFromSphericalPosition(CoordinateVector3)` instead.
/// \param[in] _xyz Vector with components (x,y,z): (East, North, Up).
/// \return Cartesian vector in the world frame.
public: GZ_DEPRECATED(8) gz::math::Vector3d LocalFromGlobalVelocity(
const gz::math::Vector3d &_xyz) const;

/// \brief Convert a Cartesian velocity vector with components East,
/// North, Up to a local cartesian frame vector XYZ.
/// This is a wrapper around `VelocityTransform(_xyz, GLOBAL, LOCAL)`
Expand All @@ -310,26 +247,6 @@ namespace gz::math
/// \brief Update coordinate transformation matrix with reference location
public: void UpdateTransformationMatrix();

/// \brief Convert between positions in SPHERICAL/ECEF/LOCAL/GLOBAL frame
/// using the reference point.
/// \deprecated To keep compatibility with Gazebo 7 and earlier, this
/// function returns incorrect result for LOCAL->SPHERICAL
/// and LOCAL->GLOBAL cases. Preferably, switch to using
/// `PositionTransform(CoordinateVector3, ..., LOCAL)` which
/// yields correct results. If you need to use this deprecated
/// overload, use coordinate type LOCAL2 to get the correct
/// result.
/// \param[in] _pos Position vector in frame defined by parameter _in.
/// If it is spherical, it has to be in radians.
/// \param[in] _in CoordinateType for input
/// \param[in] _out CoordinateType for output
/// \return Transformed coordinate using cached origin. Spherical
/// coordinates will be in radians. In case of error, `_pos` is
/// returned unchanged.
public: GZ_DEPRECATED(8) gz::math::Vector3d
PositionTransform(const gz::math::Vector3d &_pos,
const CoordinateType &_in, const CoordinateType &_out) const;

/// \brief Convert between positions in SPHERICAL/ECEF/LOCAL/GLOBAL frame
/// using the cached reference point.
/// \param[in] _pos Position vector in frame defined by parameter _in
Expand All @@ -340,25 +257,6 @@ namespace gz::math
PositionTransform(const gz::math::CoordinateVector3 &_pos,
const CoordinateType &_in, const CoordinateType &_out) const;

/// \brief Convert between velocity in ECEF/LOCAL/GLOBAL frame using the
/// cached reference point.
/// \note Spherical coordinates are not supported.
/// \deprecated To keep compatibility with Gazebo 7 and earlier, this
/// function returns incorrect result for LOCAL->SPHERICAL
/// and LOCAL->GLOBAL cases. Preferably, switch to using
/// `VelocityTransform(CoordinateVector3, ..., LOCAL)` which
/// yields correct results. If you need to use this deprecated
/// overload, use coordinate type LOCAL2 to get the correct
/// result.
/// \param[in] _vel Velocity vector in frame defined by parameter _in
/// \param[in] _in CoordinateType for input
/// \param[in] _out CoordinateType for output
/// \return Transformed velocity vector. In case of error, `_vel` is
/// returned unchanged.
public: GZ_DEPRECATED(8) gz::math::Vector3d VelocityTransform(
const gz::math::Vector3d &_vel,
const CoordinateType &_in, const CoordinateType &_out) const;

/// \brief Convert between velocity in ECEF/LOCAL/GLOBAL frame.
/// \note Spherical coordinates are not supported.
/// \param[in] _vel Velocity vector in frame defined by parameter _in
Expand Down
7 changes: 0 additions & 7 deletions include/gz/math/Stopwatch.hh
Original file line number Diff line number Diff line change
Expand Up @@ -25,13 +25,6 @@

namespace gz::math
{
// Use a steady clock
// This alias is now deprecated; please use std::chrono::steady_clock
// directly instead.
using clock
[[deprecated("As of 8.0, use std::chrono::steady_clock directly.")]]
= std::chrono::steady_clock;

// Inline bracket to help doxygen filtering.
inline namespace GZ_MATH_VERSION_NAMESPACE {
/// \class Stopwatch Stopwatch.hh gz/math/Stopwatch.hh
Expand Down
20 changes: 0 additions & 20 deletions include/gz/math/graph/Edge.hh
Original file line number Diff line number Diff line change
Expand Up @@ -203,10 +203,6 @@ namespace graph
template<typename E>
class UndirectedEdge : public Edge<E>
{
/// \brief An invalid undirected edge.
// Deprecated in favor of NullEdge().
public: static UndirectedEdge<E> GZ_DEPRECATED(8) NullEdge;

/// \brief Constructor.
/// \param[in] _vertices The vertices of the edge.
/// \param[in] _data The data stored in the edge.
Expand Down Expand Up @@ -256,22 +252,12 @@ namespace graph
}
};

/// \brief An invalid undirected edge.
// Deprecated in favor of NullEdge().
template<typename E>
UndirectedEdge<E> UndirectedEdge<E>::NullEdge(
VertexId_P(kNullId, kNullId), E(), 1.0, kNullId);

/// \brief A directed edge represents a connection between two vertices.
/// The connection is unidirectional, it's only possible to traverse the edge
/// in one direction (from the tail to the head).
template<typename E>
class DirectedEdge : public Edge<E>
{
/// \brief An invalid directed edge.
// Deprecated in favor of NullEdge().
public: static DirectedEdge<E> GZ_DEPRECATED(8) NullEdge;

/// \brief Constructor.
/// \param[in] _vertices The vertices of the edge.
/// \param[in] _data The data stored in the edge.
Expand Down Expand Up @@ -333,12 +319,6 @@ namespace graph
}
};

/// \brief An invalid directed edge.
// Deprecated in favor of NullEdge().
template<typename E>
DirectedEdge<E> DirectedEdge<E>::NullEdge(
VertexId_P(kNullId, kNullId), E(), 1.0, kNullId);

/// \brief An invalid edge.
template<typename E, typename EdgeType>
EdgeType &NullEdge()
Expand Down
9 changes: 0 additions & 9 deletions include/gz/math/graph/Vertex.hh
Original file line number Diff line number Diff line change
Expand Up @@ -52,10 +52,6 @@ namespace graph
template<typename V>
class Vertex
{
/// \brief An invalid vertex.
// Deprecated in favor of NullVertex().
public: static Vertex<V> GZ_DEPRECATED(8) NullVertex;

/// \brief Constructor.
/// \param[in] _name Non-unique vertex name.
/// \param[in] _data User information.
Expand Down Expand Up @@ -135,11 +131,6 @@ namespace graph
private: VertexId id = kNullId;
};

/// \brief An invalid vertex.
// Deprecated in favor of NullVertex().
template<typename V>
Vertex<V> Vertex<V>::NullVertex("__null__", V(), kNullId);

/// \brief An invalid vertex.
template<typename V>
Vertex<V> &NullVertex()
Expand Down
Loading

0 comments on commit 6a146ad

Please sign in to comment.