Skip to content

Commit

Permalink
Merge pull request #50 from ros2/sync-parameter-events-callbacks
Browse files Browse the repository at this point in the history
Add support for on_parameter_event to the SyncParametersClient
  • Loading branch information
esteve committed Jun 26, 2015
2 parents 8119064 + 2917aed commit 5baa519
Showing 1 changed file with 8 additions and 1 deletion.
9 changes: 8 additions & 1 deletion rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -229,7 +229,7 @@ class AsyncParametersClient

template<typename FunctorT>
typename rclcpp::subscription::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
on_parameter_event(FunctorT callback)
on_parameter_event(FunctorT & callback)
{
// TODO(esteve): remove hardcoded values
return node_->create_subscription<rcl_interfaces::msg::ParameterEvent>("parameter_events",
Expand Down Expand Up @@ -308,6 +308,13 @@ class SyncParametersClient
return rclcpp::executors::spin_node_until_future_complete(*executor_, node_, f).get();
}

template<typename FunctorT>
typename rclcpp::subscription::Subscription<rcl_interfaces::msg::ParameterEvent>::SharedPtr
on_parameter_event(FunctorT & callback)
{
return async_parameters_client_->on_parameter_event(callback);
}

private:
rclcpp::executor::Executor::SharedPtr executor_;
rclcpp::node::Node::SharedPtr node_;
Expand Down

0 comments on commit 5baa519

Please sign in to comment.