Skip to content

Commit

Permalink
Add ConditionWaitReturnCode for spin_until_complete
Browse files Browse the repository at this point in the history
Signed-off-by: Christophe Bedard <[email protected]>
  • Loading branch information
christophebedard committed Apr 4, 2024
1 parent 36d56c5 commit 0fb8046
Show file tree
Hide file tree
Showing 8 changed files with 121 additions and 32 deletions.
2 changes: 1 addition & 1 deletion rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/callback_group.cpp
src/rclcpp/client.cpp
src/rclcpp/clock.cpp
src/rclcpp/condition_wait_return_code.cpp
src/rclcpp/context.cpp
src/rclcpp/contexts/default_context.cpp
src/rclcpp/create_generic_client.cpp
Expand Down Expand Up @@ -73,7 +74,6 @@ set(${PROJECT_NAME}_SRCS
src/rclcpp/expand_topic_or_service_name.cpp
src/rclcpp/experimental/executors/events_executor/events_executor.cpp
src/rclcpp/experimental/timers_manager.cpp
src/rclcpp/future_return_code.cpp
src/rclcpp/generic_client.cpp
src/rclcpp/generic_publisher.cpp
src/rclcpp/generic_subscription.cpp
Expand Down
47 changes: 47 additions & 0 deletions rclcpp/include/rclcpp/condition_wait_return_code.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
// Copyright 2014 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef RCLCPP__CONDITION_WAIT_RETURN_CODE_HPP_
#define RCLCPP__CONDITION_WAIT_RETURN_CODE_HPP_

#include <iostream>
#include <string>

#include "rclcpp/visibility_control.hpp"

namespace rclcpp
{

/// Return codes to be used with spin_until_complete.
/**
* SUCCESS: The condition wait is complete. This does not indicate that the operation succeeded.
* INTERRUPTED: The condition wait is not complete, spinning was interrupted by Ctrl-C or another
* error.
* TIMEOUT: Spinning timed out.
*/
enum class ConditionWaitReturnCode {SUCCESS, INTERRUPTED, TIMEOUT};

/// Stream operator for ConditionWaitReturnCode.
RCLCPP_PUBLIC
std::ostream &
operator<<(std::ostream & os, const ConditionWaitReturnCode & condition_wait_return_code);

/// String conversion function for ConditionWaitReturnCode.
RCLCPP_PUBLIC
std::string
to_string(const ConditionWaitReturnCode & condition_wait_return_code);

} // namespace rclcpp

#endif // RCLCPP__CONDITION_WAIT_RETURN_CODE_HPP_
13 changes: 7 additions & 6 deletions rclcpp/include/rclcpp/executor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
#include "rclcpp/executors/executor_notify_waitable.hpp"
#include "rcpputils/scope_exit.hpp"

#include "rclcpp/condition_wait_return_code.hpp"
#include "rclcpp/context.hpp"
#include "rclcpp/contexts/default_context.hpp"
#include "rclcpp/guard_condition.hpp"
Expand Down Expand Up @@ -361,7 +362,7 @@ class Executor
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
*/
template<typename TimeRepT = int64_t, typename TimeT = std::milli>
FutureReturnCode
ConditionWaitReturnCode
spin_until_complete(
const std::function<bool(void)> & condition,
std::chrono::duration<TimeRepT, TimeT> timeout = std::chrono::duration<TimeRepT, TimeT>(-1))
Expand All @@ -376,7 +377,7 @@ class Executor

// Preliminary check, finish if condition is done already.
if (condition()) {
return FutureReturnCode::SUCCESS;
return ConditionWaitReturnCode::SUCCESS;
}

if (spinning.exchange(true)) {
Expand All @@ -388,7 +389,7 @@ class Executor
spin_once_impl(timeout_left);

if (condition()) {
return FutureReturnCode::SUCCESS;
return ConditionWaitReturnCode::SUCCESS;
}
// If the original timeout is < 0, then this is blocking, never TIMEOUT.
if (timeout_ns < std::chrono::nanoseconds::zero()) {
Expand All @@ -397,14 +398,14 @@ class Executor
// Otherwise check if we still have time to wait, return TIMEOUT if not.
auto now = std::chrono::steady_clock::now();
if (now >= end_time) {
return FutureReturnCode::TIMEOUT;
return ConditionWaitReturnCode::TIMEOUT;
}
// Subtract the elapsed time from the original timeout.
timeout_left = std::chrono::duration_cast<std::chrono::nanoseconds>(end_time - now);
}

// The condition did not pass before ok() returned false, return INTERRUPTED.
return FutureReturnCode::INTERRUPTED;
return ConditionWaitReturnCode::INTERRUPTED;
}

/// Spin (blocking) for at least the given amount of duration.
Expand All @@ -413,7 +414,7 @@ class Executor
*/
template<typename TimeRepT = int64_t, typename TimeT = std::milli>
void
spin_for(std::chrono::duration<TimeRepT, TimeT> timeout duration)
spin_for(std::chrono::duration<TimeRepT, TimeT> duration)
{
(void)spin_until_complete([]() {return false;}, duration);
}
Expand Down
10 changes: 6 additions & 4 deletions rclcpp/include/rclcpp/executors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,10 +18,12 @@
#include <future>
#include <memory>

#include "rclcpp/condition_wait_return_code.hpp"
#include "rclcpp/executors/multi_threaded_executor.hpp"
#include "rclcpp/executors/single_threaded_executor.hpp"
#include "rclcpp/executors/static_single_threaded_executor.hpp"
#include "rclcpp/experimental/executors/events_executor/events_executor.hpp"
#include "rclcpp/future_return_code.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp/utilities.hpp"
#include "rclcpp/visibility_control.hpp"
Expand Down Expand Up @@ -79,7 +81,7 @@ using rclcpp::executors::SingleThreadedExecutor;
* \return The return code, one of `SUCCESS`, `INTERRUPTED`, or `TIMEOUT`.
*/
template<typename TimeRepT = int64_t, typename TimeT = std::milli>
rclcpp::FutureReturnCode
rclcpp::ConditionWaitReturnCode
spin_node_until_complete(
rclcpp::Executor & executor,
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
Expand All @@ -95,7 +97,7 @@ spin_node_until_complete(
}

template<typename NodeT = rclcpp::Node, typename TimeRepT = int64_t, typename TimeT = std::milli>
rclcpp::FutureReturnCode
rclcpp::ConditionWaitReturnCode
spin_node_until_complete(
rclcpp::Executor & executor,
std::shared_ptr<NodeT> node_ptr,
Expand Down Expand Up @@ -156,7 +158,7 @@ spin_node_until_future_complete(
} // namespace executors

template<typename TimeRepT = int64_t, typename TimeT = std::milli>
rclcpp::FutureReturnCode
rclcpp::ConditionWaitReturnCode
spin_until_complete(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
const std::function<bool(void)> & condition,
Expand All @@ -167,7 +169,7 @@ spin_until_complete(
}

template<typename NodeT = rclcpp::Node, typename TimeRepT = int64_t, typename TimeT = std::milli>
rclcpp::FutureReturnCode
rclcpp::ConditionWaitReturnCode
spin_until_complete(
std::shared_ptr<NodeT> node_ptr,
const std::function<bool(void)> & condition,
Expand Down
13 changes: 2 additions & 11 deletions rclcpp/include/rclcpp/future_return_code.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,7 @@
#include <iostream>
#include <string>

#include "rclcpp/condition_wait_return_code.hpp"
#include "rclcpp/visibility_control.hpp"

namespace rclcpp
Expand All @@ -30,17 +31,7 @@ namespace rclcpp
* INTERRUPTED: The future is not complete, spinning was interrupted by Ctrl-C or another error.
* TIMEOUT: Spinning timed out.
*/
enum class FutureReturnCode {SUCCESS, INTERRUPTED, TIMEOUT};

/// Stream operator for FutureReturnCode.
RCLCPP_PUBLIC
std::ostream &
operator<<(std::ostream & os, const FutureReturnCode & future_return_code);

/// String conversion function for FutureReturnCode.
RCLCPP_PUBLIC
std::string
to_string(const FutureReturnCode & future_return_code);
using FutureReturnCode = ConditionWaitReturnCode;

} // namespace rclcpp

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,31 +16,31 @@
#include <string>
#include <type_traits>

#include "rclcpp/future_return_code.hpp"
#include "rclcpp/condition_wait_return_code.hpp"

namespace rclcpp
{

std::ostream &
operator<<(std::ostream & os, const rclcpp::FutureReturnCode & future_return_code)
operator<<(std::ostream & os, const rclcpp::ConditionWaitReturnCode & condition_wait_return_code)
{
return os << to_string(future_return_code);
return os << to_string(condition_wait_return_code);
}

std::string
to_string(const rclcpp::FutureReturnCode & future_return_code)
to_string(const rclcpp::ConditionWaitReturnCode & condition_wait_return_code)
{
using enum_type = std::underlying_type<FutureReturnCode>::type;
using enum_type = std::underlying_type<ConditionWaitReturnCode>::type;
std::string prefix = "Unknown enum value (";
std::string ret_as_string = std::to_string(static_cast<enum_type>(future_return_code));
switch (future_return_code) {
case FutureReturnCode::SUCCESS:
std::string ret_as_string = std::to_string(static_cast<enum_type>(condition_wait_return_code));
switch (condition_wait_return_code) {
case ConditionWaitReturnCode::SUCCESS:
prefix = "SUCCESS (";
break;
case FutureReturnCode::INTERRUPTED:
case ConditionWaitReturnCode::INTERRUPTED:
prefix = "INTERRUPTED (";
break;
case FutureReturnCode::TIMEOUT:
case ConditionWaitReturnCode::TIMEOUT:
prefix = "TIMEOUT (";
break;
}
Expand Down
6 changes: 6 additions & 0 deletions rclcpp/test/rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -109,6 +109,12 @@ ament_add_gtest(test_function_traits test_function_traits.cpp)
if(TARGET test_function_traits)
target_link_libraries(test_function_traits ${PROJECT_NAME})
endif()
ament_add_gtest(
test_condition_wait_return_code
test_condition_wait_return_code.cpp)
if(TARGET test_condition_wait_return_code)
target_link_libraries(test_condition_wait_return_code ${PROJECT_NAME})
endif()
ament_add_gtest(
test_future_return_code
test_future_return_code.cpp)
Expand Down
42 changes: 42 additions & 0 deletions rclcpp/test/rclcpp/test_condition_wait_return_code.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
// Copyright 2024 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include <gtest/gtest.h>

#include <sstream>
#include <string>

#include "rclcpp/condition_wait_return_code.hpp"

TEST(TestConditionWaitReturnCode, to_string) {
EXPECT_EQ(
"Unknown enum value (-1)", rclcpp::to_string(rclcpp::ConditionWaitReturnCode(-1)));
EXPECT_EQ(
"SUCCESS (0)", rclcpp::to_string(rclcpp::ConditionWaitReturnCode::SUCCESS));
EXPECT_EQ(
"INTERRUPTED (1)", rclcpp::to_string(rclcpp::ConditionWaitReturnCode::INTERRUPTED));
EXPECT_EQ(
"TIMEOUT (2)", rclcpp::to_string(rclcpp::ConditionWaitReturnCode::TIMEOUT));
EXPECT_EQ(
"Unknown enum value (3)", rclcpp::to_string(rclcpp::ConditionWaitReturnCode(3)));
EXPECT_EQ(
"Unknown enum value (100)", rclcpp::to_string(rclcpp::ConditionWaitReturnCode(100)));
}

TEST(TestConditionWaitReturnCode, ostream) {
std::ostringstream ostream;

ostream << rclcpp::ConditionWaitReturnCode::SUCCESS;
ASSERT_EQ("SUCCESS (0)", ostream.str());
}

0 comments on commit 0fb8046

Please sign in to comment.