Skip to content

Commit b50f9ab

Browse files
authored
refactor and improve the parameterized spin_some tests for executors (#2460)
* refactor and improve the spin_some parameterized tests for executors Signed-off-by: William Woodall <william@osrfoundation.org> * disable spin_some_max_duration for the StaticSingleThreadedExecutor and EventsExecutor Signed-off-by: William Woodall <william@osrfoundation.org> * fixup and clarify the docstring for Executor::spin_some() Signed-off-by: William Woodall <william@osrfoundation.org> * style Signed-off-by: William Woodall <william@osrfoundation.org> * review comments Signed-off-by: William Woodall <william@osrfoundation.org> --------- Signed-off-by: William Woodall <william@osrfoundation.org>
1 parent 198c82c commit b50f9ab

File tree

2 files changed

+195
-39
lines changed

2 files changed

+195
-39
lines changed

rclcpp/include/rclcpp/executor.hpp

+14-7
Original file line numberDiff line numberDiff line change
@@ -282,16 +282,23 @@ class Executor
282282
void
283283
spin_node_some(std::shared_ptr<rclcpp::Node> node);
284284

285-
/// Collect work once and execute all available work, optionally within a duration.
285+
/// Collect work once and execute all available work, optionally within a max duration.
286286
/**
287-
* This function can be overridden. The default implementation is suitable for a
288-
* single-threaded model of execution.
289-
* Adding subscriptions, timers, services, etc. with blocking callbacks will cause this function
290-
* to block (which may have unintended consequences).
287+
* This function can be overridden.
288+
* The default implementation is suitable for a single-threaded model of execution.
289+
* Adding subscriptions, timers, services, etc. with blocking or long running
290+
* callbacks may cause the function exceed the max_duration significantly.
291+
*
292+
* If there is no work to be done when this called, it will return immediately
293+
* because the collecting of available work is non-blocking.
294+
* Before each piece of ready work is executed this function checks if the
295+
* max_duration has been exceeded, and if it has it returns without starting
296+
* the execution of the next piece of work.
297+
*
298+
* If a max_duration of 0 is given, then all of the collected work will be
299+
* executed before the function returns.
291300
*
292301
* \param[in] max_duration The maximum amount of time to spend executing work, or 0 for no limit.
293-
* Note that spin_some() may take longer than this time as it only returns once max_duration has
294-
* been exceeded.
295302
*/
296303
RCLCPP_PUBLIC
297304
virtual void

rclcpp/test/rclcpp/executors/test_executors.cpp

+181-32
Original file line numberDiff line numberDiff line change
@@ -374,7 +374,20 @@ class TestWaitable : public rclcpp::Waitable
374374
{
375375
(void) data;
376376
count_++;
377-
std::this_thread::sleep_for(3ms);
377+
if (nullptr != on_execute_callback_) {
378+
on_execute_callback_();
379+
} else {
380+
// TODO(wjwwood): I don't know why this was here, but probably it should
381+
// not be there, or test cases where that is important should use the
382+
// on_execute_callback?
383+
std::this_thread::sleep_for(3ms);
384+
}
385+
}
386+
387+
void
388+
set_on_execute_callback(std::function<void()> on_execute_callback)
389+
{
390+
on_execute_callback_ = on_execute_callback;
378391
}
379392

380393
void
@@ -404,6 +417,7 @@ class TestWaitable : public rclcpp::Waitable
404417
private:
405418
size_t count_ = 0;
406419
rclcpp::GuardCondition gc_;
420+
std::function<void()> on_execute_callback_ = nullptr;
407421
};
408422

409423
TYPED_TEST(TestExecutors, spinAll)
@@ -448,45 +462,180 @@ TYPED_TEST(TestExecutors, spinAll)
448462
spinner.join();
449463
}
450464

451-
TYPED_TEST(TestExecutors, spinSome)
465+
// Helper function to convert chrono durations into a scalar that GoogleTest
466+
// can more easily compare and print.
467+
template<typename DurationT>
468+
auto
469+
to_nanoseconds_helper(DurationT duration)
470+
{
471+
return std::chrono::duration_cast<std::chrono::nanoseconds>(duration).count();
472+
}
473+
474+
// The purpose of this test is to check that the ExecutorT.spin_some() method:
475+
// - works nominally (it can execute entities)
476+
// - it can execute multiple items at once
477+
// - it does not wait for work to be available before returning
478+
TYPED_TEST(TestExecutors, spin_some)
452479
{
453480
using ExecutorType = TypeParam;
454-
ExecutorType executor;
481+
482+
// Use an isolated callback group to avoid interference from any housekeeping
483+
// items that may be in the default callback group of the node.
484+
constexpr bool automatically_add_to_executor_with_node = false;
485+
auto isolated_callback_group = this->node->create_callback_group(
486+
rclcpp::CallbackGroupType::MutuallyExclusive,
487+
automatically_add_to_executor_with_node);
488+
489+
// Check that spin_some() returns quickly when there is no work to be done.
490+
// This can be a false positive if there is somehow some work for the executor
491+
// to do that has not been considered, but the isolated callback group should
492+
// avoid that.
493+
{
494+
ExecutorType executor;
495+
executor.add_callback_group(isolated_callback_group, this->node->get_node_base_interface());
496+
497+
auto start = std::chrono::steady_clock::now();
498+
// spin_some with some non-trival "max_duration" and check that it does not
499+
// take anywhere near that long to execute.
500+
constexpr auto max_duration = 10s;
501+
executor.spin_some(max_duration);
502+
EXPECT_LT(
503+
to_nanoseconds_helper(std::chrono::steady_clock::now() - start),
504+
to_nanoseconds_helper(max_duration / 2))
505+
<< "spin_some() took a long time to execute when it should have done "
506+
<< "nothing and should not have blocked either, but this could be a "
507+
<< "false negative if the computer is really slow";
508+
}
509+
510+
// Check that having one thing ready gets executed by spin_some().
455511
auto waitable_interfaces = this->node->get_node_waitables_interface();
456-
auto my_waitable = std::make_shared<TestWaitable>();
457-
waitable_interfaces->add_waitable(my_waitable, nullptr);
458-
executor.add_node(this->node);
512+
auto my_waitable1 = std::make_shared<TestWaitable>();
513+
waitable_interfaces->add_waitable(my_waitable1, isolated_callback_group);
514+
{
515+
ExecutorType executor;
516+
executor.add_callback_group(isolated_callback_group, this->node->get_node_base_interface());
517+
518+
my_waitable1->trigger();
519+
520+
// The long duration should not matter, as executing the waitable is
521+
// non-blocking, and spin_some() should exit after completing the available
522+
// work.
523+
auto start = std::chrono::steady_clock::now();
524+
constexpr auto max_duration = 10s;
525+
executor.spin_some(max_duration);
526+
EXPECT_LT(
527+
to_nanoseconds_helper(std::chrono::steady_clock::now() - start),
528+
to_nanoseconds_helper(max_duration / 2))
529+
<< "spin_some() took a long time to execute when it should have very "
530+
<< "little to do and should not have blocked either, but this could be a "
531+
<< "false negative if the computer is really slow";
532+
533+
EXPECT_EQ(my_waitable1->get_count(), 1u)
534+
<< "spin_some() failed to execute a waitable that was triggered";
535+
}
459536

460-
// Long timeout, doesn't block test from finishing because spin_some should exit after the
461-
// first one completes.
462-
bool spin_exited = false;
463-
std::thread spinner([&spin_exited, &executor, this]() {
464-
executor.spin_some(1s);
465-
executor.remove_node(this->node, true);
466-
spin_exited = true;
467-
});
537+
// Check that multiple things being ready are executed by spin_some().
538+
auto my_waitable2 = std::make_shared<TestWaitable>();
539+
waitable_interfaces->add_waitable(my_waitable2, isolated_callback_group);
540+
{
541+
ExecutorType executor;
542+
executor.add_callback_group(isolated_callback_group, this->node->get_node_base_interface());
543+
544+
const size_t original_my_waitable1_count = my_waitable1->get_count();
545+
my_waitable1->trigger();
546+
my_waitable2->trigger();
547+
548+
// The long duration should not matter, as executing the waitable is
549+
// non-blocking, and spin_some() should exit after completing the available
550+
// work.
551+
auto start = std::chrono::steady_clock::now();
552+
constexpr auto max_duration = 10s;
553+
executor.spin_some(max_duration);
554+
EXPECT_LT(
555+
to_nanoseconds_helper(std::chrono::steady_clock::now() - start),
556+
to_nanoseconds_helper(max_duration / 2))
557+
<< "spin_some() took a long time to execute when it should have very "
558+
<< "little to do and should not have blocked either, but this could be a "
559+
<< "false negative if the computer is really slow";
560+
561+
EXPECT_EQ(my_waitable1->get_count(), original_my_waitable1_count + 1)
562+
<< "spin_some() failed to execute a waitable that was triggered";
563+
EXPECT_EQ(my_waitable2->get_count(), 1u)
564+
<< "spin_some() failed to execute a waitable that was triggered";
565+
}
566+
}
468567

469-
// Do some work until sufficient calls to the waitable occur, but keep going until either
470-
// count becomes too large, spin exits, or the 1 second timeout completes.
471-
auto start = std::chrono::steady_clock::now();
472-
while (
473-
my_waitable->get_count() <= 1 &&
474-
!spin_exited &&
475-
(std::chrono::steady_clock::now() - start < 1s))
568+
// The purpose of this test is to check that the ExecutorT.spin_some() method:
569+
// - does not continue executing after max_duration has elapsed
570+
TYPED_TEST(TestExecutors, spin_some_max_duration)
571+
{
572+
using ExecutorType = TypeParam;
573+
574+
// TODO(wjwwood): The `StaticSingleThreadedExecutor` and the `EventsExecutor`
575+
// do not properly implement max_duration (it seems), so disable this test
576+
// for them in the meantime.
577+
// see: https://github.com/ros2/rclcpp/issues/2462
578+
if (
579+
std::is_same<ExecutorType, rclcpp::executors::StaticSingleThreadedExecutor>() ||
580+
std::is_same<ExecutorType, rclcpp::experimental::executors::EventsExecutor>())
476581
{
477-
my_waitable->trigger();
478-
this->publisher->publish(test_msgs::msg::Empty());
479-
std::this_thread::sleep_for(1ms);
582+
GTEST_SKIP();
480583
}
481-
// The count of "execute" depends on whether the executor starts spinning before (1) or after (0)
482-
// the first iteration of the while loop
483-
EXPECT_LE(1u, my_waitable->get_count());
484-
waitable_interfaces->remove_waitable(my_waitable, nullptr);
485-
EXPECT_TRUE(spin_exited);
486-
// Cancel if it hasn't exited already.
487-
executor.cancel();
488584

489-
spinner.join();
585+
// Use an isolated callback group to avoid interference from any housekeeping
586+
// items that may be in the default callback group of the node.
587+
constexpr bool automatically_add_to_executor_with_node = false;
588+
auto isolated_callback_group = this->node->create_callback_group(
589+
rclcpp::CallbackGroupType::MutuallyExclusive,
590+
automatically_add_to_executor_with_node);
591+
592+
// Set up a situation with two waitables that take time to execute, such that
593+
// the time it takes to execute two waitables far exceeds the max_duration
594+
// given to spin_some(), which should result in spin_some() starting to
595+
// execute one of them, have the max duration elapse, finish executing one
596+
// of them, then returning before starting on the second.
597+
constexpr auto max_duration = 100ms; // relatively short because we expect to exceed it
598+
constexpr auto waitable_callback_duration = max_duration * 2;
599+
auto long_running_callback = [&waitable_callback_duration]() {
600+
std::this_thread::sleep_for(waitable_callback_duration);
601+
};
602+
603+
auto waitable_interfaces = this->node->get_node_waitables_interface();
604+
605+
auto my_waitable1 = std::make_shared<TestWaitable>();
606+
my_waitable1->set_on_execute_callback(long_running_callback);
607+
waitable_interfaces->add_waitable(my_waitable1, isolated_callback_group);
608+
609+
auto my_waitable2 = std::make_shared<TestWaitable>();
610+
my_waitable2->set_on_execute_callback(long_running_callback);
611+
waitable_interfaces->add_waitable(my_waitable2, isolated_callback_group);
612+
613+
ExecutorType executor;
614+
executor.add_callback_group(isolated_callback_group, this->node->get_node_base_interface());
615+
616+
auto start = std::chrono::steady_clock::now();
617+
// spin_some and check that it does not take longer than two of waitable_callback_duration,
618+
// nor significantly less than a single waitable_callback_duration.
619+
executor.spin_some(max_duration);
620+
auto spin_some_run_time = std::chrono::steady_clock::now() - start;
621+
EXPECT_GT(
622+
to_nanoseconds_helper(spin_some_run_time),
623+
to_nanoseconds_helper(waitable_callback_duration / 2))
624+
<< "spin_some() took less than half the expected time to execute a single "
625+
<< "waitable, which implies it did not actually execute one when it was "
626+
<< "expected to";
627+
EXPECT_LT(
628+
to_nanoseconds_helper(spin_some_run_time),
629+
to_nanoseconds_helper(waitable_callback_duration * 2))
630+
<< "spin_some() took longer than expected to execute by a significant margin, but "
631+
<< "this could be a false positive on a very slow computer";
632+
633+
// check that exactly one of the waitables were executed (do not depend on a specific order)
634+
size_t number_of_waitables_executed = my_waitable1->get_count() + my_waitable2->get_count();
635+
EXPECT_EQ(number_of_waitables_executed, 1u)
636+
<< "expected exactly one of the two waitables to be executed, but "
637+
<< "my_waitable1->get_count(): " << my_waitable1->get_count() << " and "
638+
<< "my_waitable2->get_count(): " << my_waitable2->get_count();
490639
}
491640

492641
// Check spin_node_until_future_complete with node base pointer

0 commit comments

Comments
 (0)