Skip to content

Commit

Permalink
Added spin_until_future_complete and spin_node_until_future_complete …
Browse files Browse the repository at this point in the history
…helper functions
  • Loading branch information
Esteve Fernandez committed Apr 20, 2015
1 parent 0f8ccd2 commit e531758
Show file tree
Hide file tree
Showing 2 changed files with 25 additions and 0 deletions.
14 changes: 14 additions & 0 deletions rclcpp/include/rclcpp/executors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,20 @@ namespace executors
using rclcpp::executors::multi_threaded_executor::MultiThreadedExecutor;
using rclcpp::executors::single_threaded_executor::SingleThreadedExecutor;

template <typename FutureT>
std::shared_future<FutureT> &
spin_node_until_future_complete(
rclcpp::executor::Executor & executor, Node::SharedPtr & node_ptr,
std::shared_future<FutureT> & future)
{
std::future_status status;
do {
executor.spin_node_some(node_ptr);
status = future.wait_for(std::chrono::seconds(0));
} while (status != std::future_status::ready && rclcpp::utilities::ok());
return future;
}

} // namespace executors
} // namespace rclcpp

Expand Down
11 changes: 11 additions & 0 deletions rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,17 @@ void spin(Node::SharedPtr & node_ptr)
executor.spin();
}

template <typename FutureT>
std::shared_future<FutureT> &
spin_until_future_complete(
Node::SharedPtr & node_ptr, std::shared_future<FutureT> & future)
{
rclcpp::executors::SingleThreadedExecutor executor;
rclcpp::executors::spin_node_until_future_complete<FutureT>(
executor, node_ptr, future);
return future;
}

} /* namespace rclcpp */

#endif /* RCLCPP_RCLCPP_RCLCPP_HPP_ */

0 comments on commit e531758

Please sign in to comment.