Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Allow spin_until_future_complete to accept std::future #1113

Merged
merged 5 commits into from
Jun 8, 2020
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -188,10 +188,10 @@ class Executor
* code.
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
*/
template<typename ResponseT, typename TimeRepT = int64_t, typename TimeT = std::milli>
template<typename FutureResponseT, typename TimeRepT = int64_t, typename TimeT = std::milli>
FutureReturnCode
spin_until_future_complete(
const std::shared_future<ResponseT> & future,
const FutureResponseT & future,
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
ivanpauno marked this conversation as resolved.
Show resolved Hide resolved
{
// TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
Expand Down
12 changes: 6 additions & 6 deletions rclcpp/include/rclcpp/executors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,12 +66,12 @@ using rclcpp::executors::SingleThreadedExecutor;
* If the time spent inside the blocking loop exceeds this timeout, return a `TIMEOUT` return code.
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
*/
template<typename ResponseT, typename TimeRepT = int64_t, typename TimeT = std::milli>
template<typename FutureResponseT, typename TimeRepT = int64_t, typename TimeT = std::milli>
rclcpp::FutureReturnCode
spin_node_until_future_complete(
rclcpp::Executor & executor,
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
const std::shared_future<ResponseT> & future,
const FutureResponseT & future,
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
{
// TODO(wjwwood): does not work recursively; can't call spin_node_until_future_complete
Expand All @@ -82,13 +82,13 @@ spin_node_until_future_complete(
return retcode;
}

template<typename NodeT = rclcpp::Node, typename ResponseT, typename TimeRepT = int64_t,
template<typename NodeT = rclcpp::Node, typename FutureResponseT, typename TimeRepT = int64_t,
typename TimeT = std::milli>
rclcpp::FutureReturnCode
spin_node_until_future_complete(
rclcpp::Executor & executor,
std::shared_ptr<NodeT> node_ptr,
const std::shared_future<ResponseT> & future,
const FutureResponseT & future,
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
{
return rclcpp::executors::spin_node_until_future_complete(
Expand All @@ -104,7 +104,7 @@ template<typename FutureT, typename TimeRepT = int64_t, typename TimeT = std::mi
rclcpp::FutureReturnCode
spin_until_future_complete(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
const std::shared_future<FutureT> & future,
const FutureT & future,
ivanpauno marked this conversation as resolved.
Show resolved Hide resolved
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
{
rclcpp::executors::SingleThreadedExecutor executor;
Expand All @@ -116,7 +116,7 @@ template<typename NodeT = rclcpp::Node, typename FutureT, typename TimeRepT = in
rclcpp::FutureReturnCode
spin_until_future_complete(
std::shared_ptr<NodeT> node_ptr,
const std::shared_future<FutureT> & future,
const FutureT & future,
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
{
return rclcpp::spin_until_future_complete(node_ptr->get_node_base_interface(), future, timeout);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -143,10 +143,10 @@ class StaticSingleThreadedExecutor : public rclcpp::Executor
* exec.add_node(node);
* exec.spin_until_future_complete(future);
*/
template<typename ResponseT, typename TimeRepT = int64_t, typename TimeT = std::milli>
template<typename FutureResponseT, typename TimeRepT = int64_t, typename TimeT = std::milli>
rclcpp::FutureReturnCode
spin_until_future_complete(
std::shared_future<ResponseT> & future,
FutureResponseT & future,
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
{
std::future_status status = future.wait_for(std::chrono::seconds(0));
Expand Down
44 changes: 44 additions & 0 deletions rclcpp/test/test_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,3 +67,47 @@ TEST_F(TestExecutors, addTemporaryNode) {
executor.add_node(std::make_shared<rclcpp::Node>("temporary_node"));
EXPECT_NO_THROW(executor.spin_some());
}

// Make sure that the spin_until_future_complete works correctly with std::future
TEST_F(TestExecutors, testSpinUntilFutureComplete) {
rclcpp::executors::SingleThreadedExecutor executor;
std::future<void> future;
rclcpp::FutureReturnCode ret;

// test success
future = std::async([]() {
return;
});
ret = executor.spin_until_future_complete(future, 1s);
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);

// test timeout
future = std::async([]() {
std::this_thread::sleep_for(20ms);
ivanpauno marked this conversation as resolved.
Show resolved Hide resolved
return;
});
ret = executor.spin_until_future_complete(future, 10ms);
EXPECT_EQ(rclcpp::FutureReturnCode::TIMEOUT, ret);
}

// Make sure that the spin_until_future_complete works correctly with std::shared_future
TEST_F(TestExecutors, testSpinUntilFutureCompleteSharedFuture) {
rclcpp::executors::SingleThreadedExecutor executor;
std::future<void> future;
rclcpp::FutureReturnCode ret;

// test success
future = std::async([]() {
return;
});
ret = executor.spin_until_future_complete(future.share(), 1s);
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);

// test timeout
future = std::async([]() {
std::this_thread::sleep_for(20ms);
ivanpauno marked this conversation as resolved.
Show resolved Hide resolved
return;
});
ret = executor.spin_until_future_complete(future.share(), 10ms);
EXPECT_EQ(rclcpp::FutureReturnCode::TIMEOUT, ret);
}