From 58e366f8cbb9c113decadf9884b927bfb8b3a967 Mon Sep 17 00:00:00 2001 From: alsora Date: Wed, 15 May 2019 16:59:15 +0100 Subject: [PATCH] updated API also for Synchronous client and fixed linter errors --- rclcpp/include/rclcpp/parameter_client.hpp | 22 ++++++++++++++++------ rclcpp/src/rclcpp/time_source.cpp | 8 ++++---- 2 files changed, 20 insertions(+), 10 deletions(-) diff --git a/rclcpp/include/rclcpp/parameter_client.hpp b/rclcpp/include/rclcpp/parameter_client.hpp index 2dcb2903bb..b35aedfb41 100644 --- a/rclcpp/include/rclcpp/parameter_client.hpp +++ b/rclcpp/include/rclcpp/parameter_client.hpp @@ -293,16 +293,26 @@ class SyncParametersClient typename rclcpp::Subscription::SharedPtr on_parameter_event(CallbackT && callback) { - return async_parameters_client_->on_parameter_event(std::forward(callback)); + return async_parameters_client_->on_parameter_event( + std::forward(callback)); } - template + /** + * The NodeT type only needs to have a method called get_node_topics_interface() + * which returns a shared_ptr to a NodeTopicsInterface, or be a + * NodeTopicsInterface pointer itself. + */ + template< + typename CallbackT, + typename NodeT> static typename rclcpp::Subscription::SharedPtr on_parameter_event( - CallbackT && callback, - rclcpp::node_interfaces::NodeTopicsInterface * node_topics) + NodeT && node, + CallbackT && callback) { - return AsyncParametersClient::on_parameter_event(std::forward(callback), node_topics); + return AsyncParametersClient::on_parameter_event( + node, + std::forward(callback)); } RCLCPP_PUBLIC @@ -328,4 +338,4 @@ class SyncParametersClient } // namespace rclcpp -#endif // RCLCPP__PARAMETER_CLIENT_HPP_ +#endif // RCLCPP__PARAMETER_CLIENT_HPP_ \ No newline at end of file diff --git a/rclcpp/src/rclcpp/time_source.cpp b/rclcpp/src/rclcpp/time_source.cpp index d17b0b5ae1..a7daa5f9df 100644 --- a/rclcpp/src/rclcpp/time_source.cpp +++ b/rclcpp/src/rclcpp/time_source.cpp @@ -103,9 +103,9 @@ void TimeSource::attachNode( } // TODO(tfoote) use parameters interface not subscribe to events via topic ticketed #609 - parameter_subscription_ = - rclcpp::AsyncParametersClient::on_parameter_event(node_topics_, std::bind(&TimeSource::on_parameter_event, - this, std::placeholders::_1)); + parameter_subscription_ = rclcpp::AsyncParametersClient::on_parameter_event( + node_topics_, + std::bind(&TimeSource::on_parameter_event, this, std::placeholders::_1)); } void TimeSource::detachNode() @@ -304,4 +304,4 @@ void TimeSource::disable_ros_time() } } -} // namespace rclcpp +} // namespace rclcpp \ No newline at end of file