From be4b1ab0a95bd0997a49395fe1b6bb683501bbad Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Mon, 1 Jul 2024 11:50:06 -0700 Subject: [PATCH 1/2] Deprecate math::clock alias Recommend using std::chrono::steady_clock directly instead of this alias. Fixes #436. Signed-off-by: Steve Peters --- Migration.md | 14 +++++++++++++ include/gz/math/Stopwatch.hh | 12 ++++++----- src/Stopwatch.cc | 40 +++++++++++++++++++----------------- src/Stopwatch_TEST.cc | 15 +++++++------- 4 files changed, 50 insertions(+), 31 deletions(-) diff --git a/Migration.md b/Migration.md index 37fffd4b4..1adfc0fdd 100644 --- a/Migration.md +++ b/Migration.md @@ -5,6 +5,20 @@ 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 7.X to 8.X + +### Breaking Changes + +1. All references to `ignition` have been removed. This includes the `ignition/` + header files, the `ignition::` namespaces, and `IGN_*` and `IGNITION_*` + macros. + +### Deprecations + +1. **Stopwatch.hh** + + The `math::clock` type alias is deprecated. Please use the underlying type + (`std::chrono::steady_clock`) directly. + ## Gazebo Math 6.X to 7.X ### Breaking Changes diff --git a/include/gz/math/Stopwatch.hh b/include/gz/math/Stopwatch.hh index 9b305e5ac..cb0e16ec7 100644 --- a/include/gz/math/Stopwatch.hh +++ b/include/gz/math/Stopwatch.hh @@ -28,7 +28,9 @@ namespace gz namespace math { // Use a steady clock - using clock = std::chrono::steady_clock; + // This alias is now deprecated; please use std::chrono::steady_clock + // directly instead. + using clock GZ_DEPRECATED(8) = std::chrono::steady_clock; // Inline bracket to help doxygen filtering. inline namespace GZ_MATH_VERSION_NAMESPACE { @@ -68,7 +70,7 @@ namespace gz /// \return The time when stopwatch was started, or /// std::chrono::steady_clock::time_point::min() if the stopwatch /// has not been started. - public: clock::time_point StartTime() const; + public: std::chrono::steady_clock::time_point StartTime() const; /// \brief Stop the stopwatch /// \return True if the stopwatch was stopped. This will return false @@ -79,7 +81,7 @@ namespace gz /// \return The time when stopwatch was last stopped, or /// std::chrono::steady_clock::time_point::min() if the stopwatch /// has never been stopped. - public: clock::time_point StopTime() const; + public: std::chrono::steady_clock::time_point StopTime() const; /// \brief Get whether the stopwatch is running. /// \return True if the stopwatch is running. @@ -94,14 +96,14 @@ namespace gz /// and stop calls. The Reset function or passing true to the Start /// function will reset this value. /// \return Total amount of elapsed run time. - public: clock::duration ElapsedRunTime() const; + public: std::chrono::steady_clock::duration ElapsedRunTime() const; /// \brief Get the amount of time that the stop watch has been /// stopped. This is the total amount of stop time, spannning all start /// and stop calls. The Reset function or passing true to the Start /// function will reset this value. /// \return Total amount of elapsed stop time. - public: clock::duration ElapsedStopTime() const; + public: std::chrono::steady_clock::duration ElapsedStopTime() const; /// \brief Equality operator. /// \param[in] _watch The watch to compare. diff --git a/src/Stopwatch.cc b/src/Stopwatch.cc index 4d407c593..07148a575 100644 --- a/src/Stopwatch.cc +++ b/src/Stopwatch.cc @@ -18,6 +18,7 @@ #include "gz/math/Stopwatch.hh" using namespace gz::math; +using steady_clock = std::chrono::steady_clock; // Private data class class gz::math::Stopwatch::Implementation @@ -26,16 +27,16 @@ class gz::math::Stopwatch::Implementation public: bool running = false; /// \brief Time point that marks the start of the real-time clock. - public: clock::time_point startTime = clock::time_point::min(); + public: steady_clock::time_point startTime = steady_clock::time_point::min(); /// \brief Time point that marks the stop of the real-time clock. - public: clock::time_point stopTime = clock::time_point::min(); + public: steady_clock::time_point stopTime = steady_clock::time_point::min(); /// \brief Amount of stop time. - public: clock::duration stopDuration = clock::duration::zero(); + public: steady_clock::duration stopDuration = steady_clock::duration::zero(); /// \brief Amount of run time. - public: clock::duration runDuration = clock::duration::zero(); + public: steady_clock::duration runDuration = steady_clock::duration::zero(); }; ////////////////////////////////////////////////// @@ -55,11 +56,11 @@ bool Stopwatch::Start(const bool _reset) if (this->dataPtr->startTime != this->dataPtr->stopTime) { this->dataPtr->stopDuration += - clock::now() - this->dataPtr->stopTime; + steady_clock::now() - this->dataPtr->stopTime; } this->dataPtr->running = true; - this->dataPtr->startTime = clock::now(); + this->dataPtr->startTime = steady_clock::now(); return true; } @@ -67,7 +68,7 @@ bool Stopwatch::Start(const bool _reset) } ////////////////////////////////////////////////// -clock::time_point Stopwatch::StartTime() const +steady_clock::time_point Stopwatch::StartTime() const { return this->dataPtr->startTime; } @@ -78,7 +79,7 @@ bool Stopwatch::Stop() if (this->dataPtr->running) { this->dataPtr->running = false; - this->dataPtr->stopTime = clock::now(); + this->dataPtr->stopTime = steady_clock::now(); this->dataPtr->runDuration += this->dataPtr->stopTime - this->dataPtr->startTime; return true; @@ -88,7 +89,7 @@ bool Stopwatch::Stop() } ////////////////////////////////////////////////// -clock::time_point Stopwatch::StopTime() const +steady_clock::time_point Stopwatch::StopTime() const { return this->dataPtr->stopTime; } @@ -103,18 +104,19 @@ bool Stopwatch::Running() const void Stopwatch::Reset() { this->dataPtr->running = false; - this->dataPtr->startTime = clock::time_point::min(); - this->dataPtr->stopTime = clock::time_point::min(); - this->dataPtr->stopDuration = clock::duration::zero(); - this->dataPtr->runDuration = clock::duration::zero(); + this->dataPtr->startTime = steady_clock::time_point::min(); + this->dataPtr->stopTime = steady_clock::time_point::min(); + this->dataPtr->stopDuration = steady_clock::duration::zero(); + this->dataPtr->runDuration = steady_clock::duration::zero(); } ////////////////////////////////////////////////// -clock::duration Stopwatch::ElapsedRunTime() const +steady_clock::duration Stopwatch::ElapsedRunTime() const { if (this->dataPtr->running) { - return clock::now() - this->dataPtr->startTime + this->dataPtr->runDuration; + return steady_clock::now() - this->dataPtr->startTime + + this->dataPtr->runDuration; } else { @@ -123,7 +125,7 @@ clock::duration Stopwatch::ElapsedRunTime() const } ////////////////////////////////////////////////// -clock::duration Stopwatch::ElapsedStopTime() const +steady_clock::duration Stopwatch::ElapsedStopTime() const { // If running, then return the stopDuration. if (this->dataPtr->running) @@ -131,14 +133,14 @@ clock::duration Stopwatch::ElapsedStopTime() const return this->dataPtr->stopDuration; } // The clock is not running, and Stop() has been called. - else if (this->dataPtr->stopTime > clock::time_point::min()) + else if (this->dataPtr->stopTime > steady_clock::time_point::min()) { return this->dataPtr->stopDuration + - (clock::now() - this->dataPtr->stopTime); + (steady_clock::now() - this->dataPtr->stopTime); } // Otherwise, the stopwatch has been reset or never started. - return clock::duration::zero(); + return steady_clock::duration::zero(); } ////////////////////////////////////////////////// diff --git a/src/Stopwatch_TEST.cc b/src/Stopwatch_TEST.cc index 1c6f8caa7..e51e2a03a 100644 --- a/src/Stopwatch_TEST.cc +++ b/src/Stopwatch_TEST.cc @@ -21,6 +21,7 @@ #include "gz/math/Stopwatch.hh" using namespace gz; +using steady_clock = std::chrono::steady_clock; ///////////////////////////////////////////////// // Helper function that runs a few tests @@ -42,7 +43,7 @@ void runTimer(math::Stopwatch &_time) // The start time should be greater than the stop time. EXPECT_GT(_time.StartTime(), _time.StopTime()); // The elapsed stop time should still be zero. - EXPECT_EQ(math::clock::duration::zero(), + EXPECT_EQ(steady_clock::duration::zero(), _time.ElapsedStopTime()); // Wait for some time... @@ -98,8 +99,8 @@ TEST(Stopwatch, Constructor) EXPECT_FALSE(watch.Running()); EXPECT_EQ(watch.StopTime(), watch.StartTime()); - EXPECT_EQ(math::clock::duration::zero(), watch.ElapsedRunTime()); - EXPECT_EQ(math::clock::duration::zero(), watch.ElapsedStopTime()); + EXPECT_EQ(steady_clock::duration::zero(), watch.ElapsedRunTime()); + EXPECT_EQ(steady_clock::duration::zero(), watch.ElapsedStopTime()); runTimer(watch); @@ -144,8 +145,8 @@ TEST(Stopwatch, StartStopReset) EXPECT_FALSE(watch.Running()); EXPECT_EQ(watch.StopTime(), watch.StartTime()); - EXPECT_EQ(math::clock::duration::zero(), watch.ElapsedRunTime()); - EXPECT_EQ(math::clock::duration::zero(), watch.ElapsedStopTime()); + EXPECT_EQ(steady_clock::duration::zero(), watch.ElapsedRunTime()); + EXPECT_EQ(steady_clock::duration::zero(), watch.ElapsedStopTime()); runTimer(watch); @@ -154,8 +155,8 @@ TEST(Stopwatch, StartStopReset) watch.Start(true); EXPECT_TRUE(watch.Running()); EXPECT_LT(watch.StopTime(), watch.StartTime()); - EXPECT_NE(math::clock::duration::zero(), watch.ElapsedRunTime()); - EXPECT_EQ(math::clock::duration::zero(), watch.ElapsedStopTime()); + EXPECT_NE(steady_clock::duration::zero(), watch.ElapsedRunTime()); + EXPECT_EQ(steady_clock::duration::zero(), watch.ElapsedStopTime()); } ///////////////////////////////////////////////// From 75ca40fb029ac5264cf61030d4dfbde47ccfdb19 Mon Sep 17 00:00:00 2001 From: Steve Peters Date: Mon, 1 Jul 2024 13:17:36 -0700 Subject: [PATCH 2/2] try using [[deprecated]] Signed-off-by: Steve Peters --- include/gz/math/Stopwatch.hh | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/include/gz/math/Stopwatch.hh b/include/gz/math/Stopwatch.hh index cb0e16ec7..fcfa40be8 100644 --- a/include/gz/math/Stopwatch.hh +++ b/include/gz/math/Stopwatch.hh @@ -30,7 +30,9 @@ namespace gz // Use a steady clock // This alias is now deprecated; please use std::chrono::steady_clock // directly instead. - using clock GZ_DEPRECATED(8) = std::chrono::steady_clock; + 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 {