Skip to content

deprecate rclcpp::spin_some and rclcpp::spin_all #2848

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

Open
wants to merge 3 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all 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
66 changes: 62 additions & 4 deletions rclcpp/include/rclcpp/executors.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,24 +28,82 @@
namespace rclcpp
{

/// Create a default single-threaded executor and execute all available work exhaustively.
/** \param[in] node_ptr Shared pointer to the node to spin. */
/**
* @brief Create a default single-threaded executor and execute all available work exhaustively.
* @param node_ptr Shared pointer to the base interface of the node to spin.
* @param max_duration max duration to spin
*
* This method is deprecated because it can lead to very bad performance if used in a loop:
* each call will create a new executor and register the node, which is an expensive operation.
* It's recommended to always manually instantiate an executor and call the methods with
* the same name on it.
* For example:
* SingleThreadedExecutor executor;
* executor.add_node(node_ptr);
* executor.spin_all(max_duration);
* If you are using a non-default context, this should be passed to the executor's constructor.
*/
[[deprecated("use SingleThreadedExecutor::spin_all instead")]]
RCLCPP_PUBLIC
void
spin_all(
rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr,
std::chrono::nanoseconds max_duration);

/**
* @brief Create a default single-threaded executor and execute all available work exhaustively.
* @param node_ptr Shared pointer to the node to spin.
* @param max_duration max duration to spin
*
* This method is deprecated because it can lead to very bad performance if used in a loop:
* each call will create a new executor and register the node, which is an expensive operation.
* It's recommended to always manually instantiate an executor and call the methods with
* the same name on it.
* For example:
* SingleThreadedExecutor executor;
* executor.add_node(node_ptr);
* executor.spin_all(max_duration);
* If you are using a non-default context, this should be passed to the executor's constructor.
*/
[[deprecated("use SingleThreadedExecutor::spin_all instead")]]
RCLCPP_PUBLIC
void
spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration);

/// Create a default single-threaded executor and execute any immediately available work.
/** \param[in] node_ptr Shared pointer to the node to spin. */
/**
* @brief Create a default single-threaded executor and execute any immediately available work.
* @param node_ptr Shared pointer to the base interface of the node to spin.
*
* This method is deprecated because it can lead to very bad performance if used in a loop:
* each call will create a new executor and register the node, which is an expensive operation.
* It's recommended to always manually instantiate an executor and call the methods with
* the same name on it.
* For example:
* SingleThreadedExecutor executor;
* executor.add_node(node_ptr);
* executor.spin_some();
* If you are using a non-default context, this should be passed to the executor's constructor.
*/
[[deprecated("use SingleThreadedExecutor::spin_some instead")]]
RCLCPP_PUBLIC
void
spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr);

/**
* @brief Create a default single-threaded executor and execute any immediately available work.
* @param node_ptr Shared pointer to the node to spin.
*
* This method is deprecated because it can lead to very bad performance if used in a loop:
* each call will create a new executor and register the node, which is an expensive operation.
* It's recommended to always manually instantiate an executor and call the methods with
* the same name on it.
* For example:
* SingleThreadedExecutor executor;
* executor.add_node(node_ptr);
* executor.spin_some();
* If you are using a non-default context, this should be passed to the executor's constructor.
*/
[[deprecated("use SingleThreadedExecutor::spin_some instead")]]
RCLCPP_PUBLIC
void
spin_some(rclcpp::Node::SharedPtr node_ptr);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,17 +64,17 @@ class EventsExecutor : public rclcpp::Executor

/// Default constructor. See the default constructor for Executor.
/**
* \param[in] options Options used to configure the executor.
* \param[in] events_queue The queue used to store events.
* \param[in] execute_timers_separate_thread If true, timers are executed in a separate
* thread. If false, timers are executed in the same thread as all other entities.
* \param[in] options Options used to configure the executor.
*/
RCLCPP_PUBLIC
EventsExecutor(
rclcpp::experimental::executors::EventsQueue::UniquePtr events_queue = std::make_unique<
rclcpp::experimental::executors::SimpleEventsQueue>(),
bool execute_timers_separate_thread = false,
const rclcpp::ExecutorOptions & options = rclcpp::ExecutorOptions());
RCLCPP_PUBLIC
EventsExecutor(
const rclcpp::ExecutorOptions & options = rclcpp::ExecutorOptions(),
rclcpp::experimental::executors::EventsQueue::UniquePtr events_queue = std::make_unique<
rclcpp::experimental::executors::SimpleEventsQueue>(),
bool execute_timers_separate_thread = false);

/// Default destructor.
RCLCPP_PUBLIC
Expand Down
2 changes: 0 additions & 2 deletions rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,8 +68,6 @@
*
* - Executors (responsible for execution of callbacks through a blocking spin):
* - rclcpp::spin()
* - rclcpp::spin_some()
* - rclcpp::spin_until_future_complete()
* - rclcpp::executors::SingleThreadedExecutor
* - rclcpp::executors::SingleThreadedExecutor::add_node()
* - rclcpp::executors::SingleThreadedExecutor::spin()
Expand Down
7 changes: 7 additions & 0 deletions rclcpp/src/rclcpp/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ class rclcpp::ExecutorImplementation {};

Executor::Executor(const std::shared_ptr<rclcpp::Context> & context)
: spinning(false),
context_(context),
entities_need_rebuild_(true),
collector_(nullptr),
wait_set_({}, {}, {}, {}, {}, {}, context)
Expand Down Expand Up @@ -186,6 +187,12 @@ Executor::add_callback_group(
void
Executor::add_node(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr, bool notify)
{
if (node_ptr->get_context() != context_)
{
throw std::runtime_error(
"add_node() called with a node with a different context from this executor");
}

this->collector_.add_node(node_ptr);

try {
Expand Down
29 changes: 17 additions & 12 deletions rclcpp/src/rclcpp/executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
// limitations under the License.

#include "rclcpp/executors.hpp"
#include "rcpputils/compile_warnings.hpp"

void
rclcpp::spin_all(
Expand All @@ -25,12 +26,6 @@ rclcpp::spin_all(
exec.spin_node_all(node_ptr, max_duration);
}

void
rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration)
{
rclcpp::spin_all(node_ptr->get_node_base_interface(), max_duration);
}

void
rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
{
Expand All @@ -40,12 +35,6 @@ rclcpp::spin_some(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr
exec.spin_node_some(node_ptr);
}

void
rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr)
{
rclcpp::spin_some(node_ptr->get_node_base_interface());
}

void
rclcpp::spin(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_ptr)
{
Expand All @@ -62,3 +51,19 @@ rclcpp::spin(rclcpp::Node::SharedPtr node_ptr)
{
rclcpp::spin(node_ptr->get_node_base_interface());
}

void
rclcpp::spin_all(rclcpp::Node::SharedPtr node_ptr, std::chrono::nanoseconds max_duration)
{
RCPPUTILS_DEPRECATION_WARNING_OFF_START
rclcpp::spin_all(node_ptr->get_node_base_interface(), max_duration);
RCPPUTILS_DEPRECATION_WARNING_OFF_STOP
}

void
rclcpp::spin_some(rclcpp::Node::SharedPtr node_ptr)
{
RCPPUTILS_DEPRECATION_WARNING_OFF_START
rclcpp::spin_some(node_ptr->get_node_base_interface());
RCPPUTILS_DEPRECATION_WARNING_OFF_STOP
}
Original file line number Diff line number Diff line change
Expand Up @@ -25,9 +25,9 @@ using namespace std::chrono_literals;
using rclcpp::experimental::executors::EventsExecutor;

EventsExecutor::EventsExecutor(
const rclcpp::ExecutorOptions & options,
rclcpp::experimental::executors::EventsQueue::UniquePtr events_queue,
bool execute_timers_separate_thread,
const rclcpp::ExecutorOptions & options)
bool execute_timers_separate_thread)
: rclcpp::Executor(options)
{
// Get ownership of the queue used to store events.
Expand Down
6 changes: 4 additions & 2 deletions rclcpp/test/benchmark/benchmark_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,19 +125,21 @@ BENCHMARK_F(ServicePerformanceTest, async_send_response)(benchmark::State & stat
auto service = node->create_service<test_msgs::srv::Empty>(empty_service_name, callback);

reset_heap_counters();
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node->get_node_base_interface());
for (auto _ : state) {
(void)_;
state.PauseTiming();
// Clear executor queue
rclcpp::spin_some(node->get_node_base_interface());
executor.spin_some();

auto request = std::make_shared<test_msgs::srv::Empty::Request>();
auto future = empty_client->async_send_request(request);
state.ResumeTiming();
benchmark::DoNotOptimize(service);
benchmark::ClobberMemory();

rclcpp::spin_until_future_complete(node->get_node_base_interface(), future);
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

do we need deprecate this too?

executor.spin_until_future_complete(future);
}
if (callback_count == 0) {
state.SkipWithError("Service callback was not called");
Expand Down
16 changes: 11 additions & 5 deletions rclcpp/test/rclcpp/executors/test_executors.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -804,27 +804,33 @@ TEST(TestExecutors, testSpinUntilFutureCompleteNodePtr)
}

// Check spin functions with non default context
TEST(TestExecutors, testSpinWithNonDefaultContext)
TYPED_TEST(TestExecutors, testSpinWithNonDefaultContext)
{
using ExecutorType = TypeParam;

auto non_default_context = std::make_shared<rclcpp::Context>();
non_default_context->init(0, nullptr);

{
auto node =
std::make_unique<rclcpp::Node>("node", rclcpp::NodeOptions().context(non_default_context));

EXPECT_NO_THROW(rclcpp::spin_some(node->get_node_base_interface()));
rclcpp::ExecutorOptions options;
options.context = non_default_context;
ExecutorType executor(options);
EXPECT_NO_THROW(executor.add_node(node->get_node_base_interface()));

EXPECT_NO_THROW(executor.spin_some());

EXPECT_NO_THROW(rclcpp::spin_all(node->get_node_base_interface(), 1s));
EXPECT_NO_THROW(executor.spin_all(1s));

auto check_spin_until_future_complete = [&]() {
std::promise<bool> promise;
std::future<bool> future = promise.get_future();
promise.set_value(true);

auto shared_future = future.share();
auto ret = rclcpp::spin_until_future_complete(
node->get_node_base_interface(), shared_future, 1s);
auto ret = executor.spin_until_future_complete(shared_future, 1s);
EXPECT_EQ(rclcpp::FutureReturnCode::SUCCESS, ret);
};
EXPECT_NO_THROW(check_spin_until_future_complete());
Expand Down
26 changes: 18 additions & 8 deletions rclcpp/test/rclcpp/test_client_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,10 +112,12 @@ class TestAllClientTypesWithServer : public ::testing::Test
auto req_id = client->async_send_request(request, std::move(callback));

auto start = std::chrono::steady_clock::now();
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
while (!received_response &&
(std::chrono::steady_clock::now() - start) < timeout)
{
rclcpp::spin_some(node);
executor.spin_some();
}

if (!received_response) {
Expand Down Expand Up @@ -356,10 +358,12 @@ TYPED_TEST(TestAllClientTypesWithServer, on_new_response_callback)

this->template async_send_request<ClientType, test_msgs::srv::Empty::Request>(client, request);
auto start = std::chrono::steady_clock::now();
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(server_node);
while (server_requests_count == 0 &&
(std::chrono::steady_clock::now() - start) < std::chrono::seconds(10))
{
rclcpp::spin_some(server_node);
executor.spin_some();
}

ASSERT_EQ(server_requests_count, 1u);
Expand All @@ -380,7 +384,7 @@ TYPED_TEST(TestAllClientTypesWithServer, on_new_response_callback)
while (server_requests_count == 1 &&
(std::chrono::steady_clock::now() - start) < std::chrono::seconds(10))
{
rclcpp::spin_some(server_node);
executor.spin_some();
}

ASSERT_EQ(server_requests_count, 2u);
Expand All @@ -402,7 +406,7 @@ TYPED_TEST(TestAllClientTypesWithServer, on_new_response_callback)
while (server_requests_count < 5 &&
(std::chrono::steady_clock::now() - start) < std::chrono::seconds(10))
{
rclcpp::spin_some(server_node);
executor.spin_some();
}

ASSERT_EQ(server_requests_count, 5u);
Expand Down Expand Up @@ -492,10 +496,12 @@ void client_async_send_request_callback_with_request(
auto req_id = client->async_send_request(request, std::move(callback));

auto start = std::chrono::steady_clock::now();
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
while (!received_response &&
(std::chrono::steady_clock::now() - start) < std::chrono::seconds(1))
{
rclcpp::spin_some(node);
executor.spin_some();
}
EXPECT_TRUE(received_response);
EXPECT_FALSE(client->remove_pending_request(req_id));
Expand Down Expand Up @@ -553,25 +559,29 @@ void client_qos_depth(rclcpp::Node::SharedPtr node)
}

auto start = std::chrono::steady_clock::now();
rclcpp::executors::SingleThreadedExecutor server_executor;
server_executor.add_node(server_node);
while ((server_cb_count_ < client_requests) &&
(std::chrono::steady_clock::now() - start) < 2s)
{
rclcpp::spin_some(server_node);
server_executor.spin_some();
std::this_thread::sleep_for(2ms);
}

EXPECT_GT(server_cb_count_, client_qos_profile.depth());

start = std::chrono::steady_clock::now();
rclcpp::executors::SingleThreadedExecutor client_executor;
client_executor.add_node(node);
while ((client_cb_count_ < client_qos_profile.depth()) &&
(std::chrono::steady_clock::now() - start) < 1s)
{
rclcpp::spin_some(node);
client_executor.spin_some();
}

// Spin an extra time to check if client QoS depth has been ignored,
// so more client callbacks might be called than expected.
rclcpp::spin_some(node);
client_executor.spin_some();

EXPECT_EQ(client_cb_count_, client_qos_profile.depth());
}
Expand Down
4 changes: 3 additions & 1 deletion rclcpp/test/rclcpp/test_create_timer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,9 @@ TEST(TestCreateTimer, timer_executes)
timer->cancel();
});

rclcpp::spin_some(node);
rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(node);
executor.spin_some();

ASSERT_TRUE(got_callback);
rclcpp::shutdown();
Expand Down
Loading