Skip to content

Commit

Permalink
created static functions
Browse files Browse the repository at this point in the history
Signed-off-by: alberto <asoragna@irobot.com>
  • Loading branch information
alberto committed Apr 8, 2019
1 parent af9ae4a commit ca38312
Show file tree
Hide file tree
Showing 2 changed files with 39 additions and 8 deletions.
37 changes: 37 additions & 0 deletions rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -134,6 +134,34 @@ class AsyncParametersClient
std::make_shared<Alloc>());
}

template<
typename CallbackT,
typename Alloc = std::allocator<void>,
typename SubscriptionT =
rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent, Alloc>>
static typename rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
on_parameter_event(
CallbackT && callback,
rclcpp::node_interfaces::NodeTopicsInterface * node_topics)
{
using rclcpp::message_memory_strategy::MessageMemoryStrategy;
auto msg_mem_strat =
MessageMemoryStrategy<rcl_interfaces::msg::ParameterEvent, Alloc>::create_default();

using rcl_interfaces::msg::ParameterEvent;
return rclcpp::create_subscription<
ParameterEvent, CallbackT, Alloc, ParameterEvent, SubscriptionT>(
node_topics,
"parameter_events",
std::forward<CallbackT>(callback),
rmw_qos_profile_default,
nullptr, // group,
false, // ignore_local_publications,
false, // use_intra_process_comms_,
msg_mem_strat,
std::make_shared<Alloc>());
}

RCLCPP_PUBLIC
bool
service_is_ready() const;
Expand Down Expand Up @@ -274,6 +302,15 @@ class SyncParametersClient
return async_parameters_client_->on_parameter_event(std::forward<CallbackT>(callback));
}

template<typename CallbackT>
static typename rclcpp::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
on_parameter_event(
CallbackT && callback,
rclcpp::node_interfaces::NodeTopicsInterface * node_topics)
{
return AsyncParametersClient::on_parameter_event(std::forward<CallbackT>(callback), node_topics);
}

RCLCPP_PUBLIC
bool
service_is_ready() const
Expand Down
10 changes: 2 additions & 8 deletions rclcpp/src/rclcpp/time_source.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,15 +95,9 @@ void TimeSource::attachNode(
}

// TODO(tfoote) use parameters interface not subscribe to events via topic ticketed #609
parameter_client_ = std::make_shared<rclcpp::AsyncParametersClient>(
node_base_,
node_topics_,
node_graph_,
node_services_
);
parameter_subscription_ =
parameter_client_->on_parameter_event(std::bind(&TimeSource::on_parameter_event,
this, std::placeholders::_1));
rclcpp::AsyncParametersClient::on_parameter_event(std::bind(&TimeSource::on_parameter_event,
this, std::placeholders::_1), node_topics_.get());
}

void TimeSource::detachNode()
Expand Down

0 comments on commit ca38312

Please sign in to comment.