Merge pull request #113 from ros2/spin_until_future_complete

Pass timeout to spin_until_future_complete
This commit is contained in:
Jackie Kay 2015-09-16 09:34:49 -07:00
commit 6f075175d2

View file

@ -97,14 +97,15 @@ void spin(Node::SharedPtr node_ptr)
executor.spin(); executor.spin();
} }
template<typename FutureT> template<typename FutureT, typename TimeT = std::milli>
rclcpp::executors::FutureReturnCode rclcpp::executors::FutureReturnCode
spin_until_future_complete( spin_until_future_complete(
Node::SharedPtr node_ptr, std::shared_future<FutureT> & future) Node::SharedPtr node_ptr, std::shared_future<FutureT> & future,
std::chrono::duration<int64_t, TimeT> timeout = std::chrono::duration<int64_t, TimeT>(-1))
{ {
rclcpp::executors::SingleThreadedExecutor executor; rclcpp::executors::SingleThreadedExecutor executor;
return rclcpp::executors::spin_node_until_future_complete<FutureT>( return rclcpp::executors::spin_node_until_future_complete<FutureT>(
executor, node_ptr, future); executor, node_ptr, future, timeout);
} }
} /* namespace rclcpp */ } /* namespace rclcpp */