Skip to content

Commit 09cad72

Browse files
Janosch MachowinskiJanosch Machowinski
authored andcommitted
test: Added test for missed trigger event during execution
Signed-off-by: Janosch Machowinski <[email protected]>
1 parent eb39a3a commit 09cad72

File tree

1 file changed

+80
-2
lines changed

1 file changed

+80
-2
lines changed

rclcpp/test/rclcpp/executors/test_executors.cpp

Lines changed: 80 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,32 @@
4141

4242
using namespace std::chrono_literals;
4343

44+
45+
template<typename T>
46+
class TestExecutorsOnlyNode : public ::testing::Test
47+
{
48+
public:
49+
void SetUp()
50+
{
51+
rclcpp::init(0, nullptr);
52+
53+
const auto test_info = ::testing::UnitTest::GetInstance()->current_test_info();
54+
std::stringstream test_name;
55+
test_name << test_info->test_case_name() << "_" << test_info->name();
56+
node = std::make_shared<rclcpp::Node>("node", test_name.str());
57+
58+
}
59+
60+
void TearDown()
61+
{
62+
node.reset();
63+
64+
rclcpp::shutdown();
65+
}
66+
67+
rclcpp::Node::SharedPtr node;
68+
};
69+
4470
template<typename T>
4571
class TestExecutors : public ::testing::Test
4672
{
@@ -122,6 +148,8 @@ class ExecutorTypeNames
122148
// is updated.
123149
TYPED_TEST_SUITE(TestExecutors, ExecutorTypes, ExecutorTypeNames);
124150

151+
TYPED_TEST_SUITE(TestExecutorsOnlyNode, ExecutorTypes, ExecutorTypeNames);
152+
125153
// StaticSingleThreadedExecutor is not included in these tests for now, due to:
126154
// https://github.com/ros2/rclcpp/issues/1219
127155
using StandardExecutors =
@@ -398,8 +426,6 @@ class TestWaitable : public rclcpp::Waitable
398426
}
399427
}
400428
return false;
401-
(void)wait_set;
402-
return true;
403429
}
404430

405431
std::shared_ptr<void>
@@ -494,6 +520,58 @@ TYPED_TEST(TestExecutors, spinAll)
494520
spinner.join();
495521
}
496522

523+
TYPED_TEST(TestExecutorsOnlyNode, missing_event)
524+
{
525+
using ExecutorType = TypeParam;
526+
ExecutorType executor;
527+
528+
rclcpp::Node::SharedPtr node(this->node);
529+
auto callback_group = node->create_callback_group(
530+
rclcpp::CallbackGroupType::MutuallyExclusive,
531+
true);
532+
533+
auto waitable_interfaces = node->get_node_waitables_interface();
534+
auto my_waitable = std::make_shared<TestWaitable>();
535+
auto my_waitable2 = std::make_shared<TestWaitable>();
536+
waitable_interfaces->add_waitable(my_waitable, callback_group);
537+
waitable_interfaces->add_waitable(my_waitable2, callback_group);
538+
executor.add_node(this->node);
539+
540+
my_waitable->trigger();
541+
my_waitable2->trigger();
542+
543+
// a node has some default subscribers, that need to get executed first, therefore the loop
544+
for (int i = 0; i < 10; i++) {
545+
executor.spin_once(std::chrono::milliseconds(10));
546+
if (my_waitable->get_count() > 0) {
547+
// stop execution, after the first waitable has been executed
548+
break;
549+
}
550+
}
551+
552+
EXPECT_EQ(1u, my_waitable->get_count());
553+
EXPECT_EQ(0u, my_waitable2->get_count());
554+
555+
// block the callback group, this is something that may happen during multi threaded execution
556+
// This removes my_waitable2 from the list of ready events, and triggers a call to wait_for_work
557+
callback_group->can_be_taken_from().exchange(false);
558+
559+
//now there should be no ready event
560+
executor.spin_once(std::chrono::milliseconds(10));
561+
562+
EXPECT_EQ(1u, my_waitable->get_count());
563+
EXPECT_EQ(0u, my_waitable2->get_count());
564+
565+
//unblock the callback group
566+
callback_group->can_be_taken_from().exchange(true);
567+
568+
//now the second waitable should get processed
569+
executor.spin_once(std::chrono::milliseconds(10));
570+
571+
EXPECT_EQ(1u, my_waitable->get_count());
572+
EXPECT_EQ(1u, my_waitable2->get_count());
573+
}
574+
497575
TYPED_TEST(TestExecutors, spinSome)
498576
{
499577
using ExecutorType = TypeParam;

0 commit comments

Comments
 (0)