From 5d6d65bfc612ca4a0170d2fe9b006d0907ee202a Mon Sep 17 00:00:00 2001 From: methylDragon Date: Thu, 3 Nov 2022 13:51:21 -0700 Subject: [PATCH] Refine wait_for_valid signature Signed-off-by: methylDragon --- rclcpp/include/rclcpp/clock.hpp | 6 +++--- rclcpp/src/rclcpp/clock.cpp | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/rclcpp/include/rclcpp/clock.hpp b/rclcpp/include/rclcpp/clock.hpp index 197b684cf7..82532e52e9 100644 --- a/rclcpp/include/rclcpp/clock.hpp +++ b/rclcpp/include/rclcpp/clock.hpp @@ -162,7 +162,7 @@ class Clock /** * Wait for clock to become valid. * - * \param context the context to wait in. + * \param context the context to wait in * \return true if clock was or became valid * \throws std::runtime_error if the context is invalid or clock is not rcl_clock_valid */ @@ -178,7 +178,7 @@ class Clock * \param timeout the maximum time to wait for. * \param context the context to wait in. * \param wait_tick_ns the time to wait between each iteration of the wait loop (in nanoseconds). - * \return true if the clock is active + * \return true if clock was or became valid * \throws std::runtime_error if the context is invalid or clock is not rcl_clock_valid */ RCLCPP_PUBLIC @@ -186,7 +186,7 @@ class Clock wait_for_valid( const rclcpp::Duration & timeout, Context::SharedPtr context = contexts::get_global_default_context(), - Duration wait_tick_ns = Duration(0, static_cast(1e7))); + const rclcpp::Duration & wait_tick_ns = rclcpp::Duration(0, static_cast(1e7))); /** * Returns the clock of the type `RCL_ROS_TIME` is active. diff --git a/rclcpp/src/rclcpp/clock.cpp b/rclcpp/src/rclcpp/clock.cpp index e0b46e6b12..ab18190294 100644 --- a/rclcpp/src/rclcpp/clock.cpp +++ b/rclcpp/src/rclcpp/clock.cpp @@ -227,7 +227,7 @@ bool Clock::wait_for_valid( const Duration & timeout, Context::SharedPtr context, - Duration wait_tick_ns) + const Duration & wait_tick_ns) { if (!context || !context->is_valid()) { throw std::runtime_error("context cannot be slept with because it's invalid");