Skip to content

Commit

Permalink
Deprecate RealtimeClock class (#244)
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Dec 20, 2024
1 parent 246e57e commit 5d0f707
Show file tree
Hide file tree
Showing 2 changed files with 7 additions and 1 deletion.
2 changes: 1 addition & 1 deletion include/realtime_tools/realtime_clock.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@

namespace realtime_tools
{
class RealtimeClock
class [[deprecated("Use rclcpp::Clock or std::chrono::steady_clock instead")]] RealtimeClock
{
public:
/**
Expand Down
6 changes: 6 additions & 0 deletions test/realtime_clock_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,10 @@
#include "rclcpp/utilities.hpp"
#include "realtime_tools/realtime_clock.hpp"

// Disable deprecated warnings
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wdeprecated-declarations"

using realtime_tools::RealtimeClock;

TEST(RealtimeClock, get_system_time)
Expand All @@ -59,3 +63,5 @@ TEST(RealtimeClock, get_system_time)
}
rclcpp::shutdown();
}

#pragma GCC diagnostic pop

0 comments on commit 5d0f707

Please sign in to comment.