From 4d203ae45fc623f1a4296621e80eaa8a677483b3 Mon Sep 17 00:00:00 2001 From: Amadeusz Szymko Date: Tue, 4 Mar 2025 22:05:29 +0900 Subject: [PATCH] feat: const func & fix typos (#9) Signed-off-by: Amadeusz Szymko --- .../managed_transform_buffer_provider.hpp | 6 +++--- .../src/managed_transform_buffer.cpp | 1 - .../src/managed_transform_buffer_provider.cpp | 19 +++++++++---------- 3 files changed, 12 insertions(+), 14 deletions(-) diff --git a/managed_transform_buffer/include/managed_transform_buffer/managed_transform_buffer_provider.hpp b/managed_transform_buffer/include/managed_transform_buffer/managed_transform_buffer_provider.hpp index 9b6c903..aaa6b40 100644 --- a/managed_transform_buffer/include/managed_transform_buffer/managed_transform_buffer_provider.hpp +++ b/managed_transform_buffer/include/managed_transform_buffer/managed_transform_buffer_provider.hpp @@ -173,7 +173,7 @@ class ManagedTransformBufferProvider */ std::optional lookupTransform( const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time, - const tf2::Duration & timeout, const rclcpp::Logger & logger); + const tf2::Duration & timeout, const rclcpp::Logger & logger) const; /** @brief Traverse TF tree built by local TF listener. * @@ -185,7 +185,7 @@ class ManagedTransformBufferProvider */ TraverseResult traverseTree( const std::string & target_frame, const std::string & source_frame, - const tf2::Duration & timeout, const rclcpp::Logger & logger); + const tf2::Duration & timeout, const rclcpp::Logger & logger) const; /** @brief Get a dynamic transform from the TF buffer. * @@ -198,7 +198,7 @@ class ManagedTransformBufferProvider */ std::optional getDynamicTransform( const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time, - const tf2::Duration & timeout, const rclcpp::Logger & logger); + const tf2::Duration & timeout, const rclcpp::Logger & logger) const; /** @brief Get a static transform from local TF buffer. * diff --git a/managed_transform_buffer/src/managed_transform_buffer.cpp b/managed_transform_buffer/src/managed_transform_buffer.cpp index a188e45..2438521 100644 --- a/managed_transform_buffer/src/managed_transform_buffer.cpp +++ b/managed_transform_buffer/src/managed_transform_buffer.cpp @@ -42,7 +42,6 @@ std::optional ManagedTransformBuffer::getTransformgetTransform(target_frame, source_frame, time, timeout, logger); return provider_->getTransform(target_frame, source_frame, time, timeout, logger); } diff --git a/managed_transform_buffer/src/managed_transform_buffer_provider.cpp b/managed_transform_buffer/src/managed_transform_buffer_provider.cpp index 01d2f9f..fe123a5 100644 --- a/managed_transform_buffer/src/managed_transform_buffer_provider.cpp +++ b/managed_transform_buffer/src/managed_transform_buffer_provider.cpp @@ -48,12 +48,12 @@ ManagedTransformBufferProvider & ManagedTransformBufferProvider::getInstance( if (instance.isStatic()) { instance.registerAsDynamic(); } - if (clock_type != instance.clock_->get_clock_type()) { - RCLCPP_WARN_THROTTLE( - instance.logger_, *instance.clock_, 3000, - "Input clock type does not match (%d vs. %d). Input clock type will be ignored.", - clock_type, instance.clock_->get_clock_type()); - } + } + if (clock_type != instance.clock_->get_clock_type()) { + RCLCPP_WARN_THROTTLE( + instance.logger_, *instance.clock_, 3000, + "Input clock type does not match (%d vs. %d). Input clock type will be ignored.", clock_type, + instance.clock_->get_clock_type()); } return instance; } @@ -191,10 +191,9 @@ void ManagedTransformBufferProvider::tfCallback( std::optional ManagedTransformBufferProvider::lookupTransform( const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time, - const tf2::Duration & timeout, const rclcpp::Logger & logger) + const tf2::Duration & timeout, const rclcpp::Logger & logger) const { try { - auto x = node_->get_logger(); auto tf = tf_buffer_->lookupTransform(target_frame, source_frame, time, timeout); return std::make_optional(tf); } catch (const tf2::TransformException & ex) { @@ -207,7 +206,7 @@ std::optional ManagedTransformBufferProvider::lookupTransform( TraverseResult ManagedTransformBufferProvider::traverseTree( const std::string & target_frame, const std::string & source_frame, const tf2::Duration & timeout, - const rclcpp::Logger & logger) + const rclcpp::Logger & logger) const { std::atomic timeout_reached{false}; @@ -285,7 +284,7 @@ TraverseResult ManagedTransformBufferProvider::traverseTree( std::optional ManagedTransformBufferProvider::getDynamicTransform( const std::string & target_frame, const std::string & source_frame, const tf2::TimePoint & time, - const tf2::Duration & timeout, const rclcpp::Logger & logger) + const tf2::Duration & timeout, const rclcpp::Logger & logger) const { return lookupTransform(target_frame, source_frame, time, timeout, logger); }