Skip to content

Commit

Permalink
updated API also for Synchronous client and fixed linter errors
Browse files Browse the repository at this point in the history
  • Loading branch information
alsora committed May 15, 2019
1 parent 031dd7c commit 58e366f
Show file tree
Hide file tree
Showing 2 changed files with 20 additions and 10 deletions.
22 changes: 16 additions & 6 deletions rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -293,16 +293,26 @@ class SyncParametersClient
typename rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
on_parameter_event(CallbackT && callback)
{
return async_parameters_client_->on_parameter_event(std::forward<CallbackT>(callback));
return async_parameters_client_->on_parameter_event(
std::forward<CallbackT>(callback));
}

template<typename CallbackT>
/**
* 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<rcl_interfaces::msg::ParameterEvent>::SharedPtr
on_parameter_event(
CallbackT && callback,
rclcpp::node_interfaces::NodeTopicsInterface * node_topics)
NodeT && node,
CallbackT && callback)
{
return AsyncParametersClient::on_parameter_event(std::forward<CallbackT>(callback), node_topics);
return AsyncParametersClient::on_parameter_event(
node,
std::forward<CallbackT>(callback));
}

RCLCPP_PUBLIC
Expand All @@ -328,4 +338,4 @@ class SyncParametersClient

} // namespace rclcpp

#endif // RCLCPP__PARAMETER_CLIENT_HPP_
#endif // RCLCPP__PARAMETER_CLIENT_HPP_
8 changes: 4 additions & 4 deletions rclcpp/src/rclcpp/time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down Expand Up @@ -304,4 +304,4 @@ void TimeSource::disable_ros_time()
}
}

} // namespace rclcpp
} // namespace rclcpp

0 comments on commit 58e366f

Please sign in to comment.