Skip to content

Commit b452e49

Browse files
fmricoJanosch Machowinski
authored and
Janosch Machowinski
committed
Add executor tests for testing destroying nodes
Signed-off-by: Francisco Martín Rico <[email protected]>
1 parent c8449f7 commit b452e49

File tree

1 file changed

+116
-0
lines changed

1 file changed

+116
-0
lines changed

rclcpp/test/rclcpp/executors/test_executors.cpp

+116
Original file line numberDiff line numberDiff line change
@@ -945,6 +945,59 @@ TYPED_TEST(TestExecutors, dropSomeTimer)
945945
ASSERT_TRUE(timer1_works || timer2_works);
946946
}
947947

948+
TYPED_TEST(TestExecutors, dropSomeNodeWithTimer)
949+
{
950+
using ExecutorType = TypeParam;
951+
ExecutorType executor;
952+
953+
auto node1 = std::make_shared<rclcpp::Node>("test_node_1");
954+
auto node2 = std::make_shared<rclcpp::Node>("test_node_2");
955+
956+
bool timer1_works = false;
957+
bool timer2_works = false;
958+
959+
auto timer1 = node1->create_timer(std::chrono::milliseconds(10), [&timer1_works]() {
960+
timer1_works = true;
961+
});
962+
auto timer2 = node2->create_timer(std::chrono::milliseconds(10), [&timer2_works]() {
963+
timer2_works = true;
964+
});
965+
966+
executor.add_node(node1);
967+
executor.add_node(node2);
968+
969+
// first let's make sure that both timers work
970+
auto max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
971+
while(!timer1_works || !timer2_works) {
972+
// let the executor pick up the node and the timers
973+
executor.spin_all(std::chrono::milliseconds(10));
974+
975+
const auto cur_time = std::chrono::steady_clock::now();
976+
ASSERT_LT(cur_time, max_end_time);
977+
if(cur_time > max_end_time) {
978+
return;
979+
}
980+
}
981+
982+
// delete node 1.
983+
node1 = nullptr;
984+
985+
timer2_works = false;
986+
max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
987+
while(!timer2_works) {
988+
// let the executor pick up the node and the timer
989+
executor.spin_all(std::chrono::milliseconds(10));
990+
991+
const auto cur_time = std::chrono::steady_clock::now();
992+
ASSERT_LT(cur_time, max_end_time);
993+
if(cur_time > max_end_time) {
994+
return;
995+
}
996+
}
997+
998+
ASSERT_TRUE(timer2_works);
999+
}
1000+
9481001
TYPED_TEST(TestExecutors, dropSomeSubscription)
9491002
{
9501003
using ExecutorType = TypeParam;
@@ -1007,3 +1060,66 @@ TYPED_TEST(TestExecutors, dropSomeSubscription)
10071060

10081061
ASSERT_TRUE(sub1_works || sub2_works);
10091062
}
1063+
1064+
TYPED_TEST(TestExecutors, dropSomeNodesWithSubscription)
1065+
{
1066+
using ExecutorType = TypeParam;
1067+
ExecutorType executor;
1068+
1069+
auto node = std::make_shared<rclcpp::Node>("test_node");
1070+
auto node1 = std::make_shared<rclcpp::Node>("test_node_1");
1071+
auto node2 = std::make_shared<rclcpp::Node>("test_node_2");
1072+
1073+
bool sub1_works = false;
1074+
bool sub2_works = false;
1075+
1076+
auto sub1 = node1->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
1077+
[&sub1_works](const test_msgs::msg::Empty & msg) {
1078+
sub1_works = true;
1079+
});
1080+
auto sub2 = node2->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
1081+
[&sub2_works](const test_msgs::msg::Empty & msg) {
1082+
sub2_works = true;
1083+
});
1084+
1085+
auto pub = node->create_publisher<test_msgs::msg::Empty>("/test_drop", 10);
1086+
1087+
executor.add_node(node);
1088+
executor.add_node(node1);
1089+
executor.add_node(node2);
1090+
1091+
// first let's make sure that both subscribers work
1092+
auto max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
1093+
while(!sub1_works || !sub2_works) {
1094+
pub->publish(test_msgs::msg::Empty());
1095+
1096+
// let the executor pick up the node and the timers
1097+
executor.spin_all(std::chrono::milliseconds(10));
1098+
1099+
const auto cur_time = std::chrono::steady_clock::now();
1100+
ASSERT_LT(cur_time, max_end_time);
1101+
if(cur_time > max_end_time) {
1102+
return;
1103+
}
1104+
}
1105+
1106+
// delete node 2.
1107+
node2 = nullptr;
1108+
1109+
sub1_works = false;
1110+
max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
1111+
while(!sub1_works) {
1112+
pub->publish(test_msgs::msg::Empty());
1113+
1114+
// let the executor pick up the node and the timers
1115+
executor.spin_all(std::chrono::milliseconds(10));
1116+
1117+
const auto cur_time = std::chrono::steady_clock::now();
1118+
ASSERT_LT(cur_time, max_end_time);
1119+
if(cur_time > max_end_time) {
1120+
return;
1121+
}
1122+
}
1123+
1124+
ASSERT_TRUE(sub1_works);
1125+
}

0 commit comments

Comments
 (0)