Skip to content

Commit

Permalink
Add wait_for_service and service_is_ready for SyncParametersClient (#356
Browse files Browse the repository at this point in the history
)
  • Loading branch information
dhood authored Aug 17, 2017
1 parent 98dded0 commit 1245005
Showing 1 changed file with 15 additions and 0 deletions.
15 changes: 15 additions & 0 deletions rclcpp/include/rclcpp/parameter_client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -218,6 +218,21 @@ class SyncParametersClient
return async_parameters_client_->on_parameter_event(std::forward<CallbackT>(callback));
}

RCLCPP_PUBLIC
bool
service_is_ready() const
{
return async_parameters_client_->service_is_ready();
}

template<typename RatioT = std::milli>
bool
wait_for_service(
std::chrono::duration<int64_t, RatioT> timeout = std::chrono::duration<int64_t, RatioT>(-1))
{
return async_parameters_client_->wait_for_service(timeout);
}

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

0 comments on commit 1245005

Please sign in to comment.