Skip to content

Commit 605251b

Browse files
jmachowinskiJanosch Machowinskifmrico
authored
Test case and fix for for #2652 (#2713)
Signed-off-by: Janosch Machowinski <[email protected]> Signed-off-by: Francisco Martín Rico <[email protected]> Co-authored-by: Janosch Machowinski <[email protected]> Co-authored-by: Francisco Martín Rico <[email protected]>
1 parent f6b80ab commit 605251b

File tree

3 files changed

+224
-0
lines changed

3 files changed

+224
-0
lines changed

rclcpp/include/rclcpp/wait_set_policies/dynamic_storage.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -216,6 +216,11 @@ class DynamicStorage : public rclcpp::wait_set_policies::detail::StoragePolicyCo
216216
shared_waitables_
217217
);
218218

219+
if (this->needs_pruning_) {
220+
this->storage_prune_deleted_entities();
221+
this->needs_pruning_ = false;
222+
}
223+
219224
this->storage_release_ownerships();
220225
}
221226

rclcpp/include/rclcpp/wait_set_policies/static_storage.hpp

+9
Original file line numberDiff line numberDiff line change
@@ -160,6 +160,15 @@ class StaticStorage : public rclcpp::wait_set_policies::detail::StoragePolicyCom
160160
services_,
161161
waitables_
162162
);
163+
164+
if(this->needs_pruning_) {
165+
// we need to throw here, as the indexing of the rcl_waitset is broken,
166+
// in case of invalid entries
167+
168+
throw std::runtime_error(
169+
"StaticStorage::storage_rebuild_rcl_wait_set(): entity weak_ptr "
170+
"unexpectedly expired in static entity storage");
171+
}
163172
}
164173

165174
// storage_add_subscription() explicitly not declared here

rclcpp/test/rclcpp/executors/test_executors.cpp

+210
Original file line numberDiff line numberDiff line change
@@ -889,3 +889,213 @@ TYPED_TEST(TestExecutors, testRaceDropCallbackGroupFromSecondThread)
889889
executor.cancel();
890890
executor_thread.join();
891891
}
892+
893+
TYPED_TEST(TestExecutors, dropSomeTimer)
894+
{
895+
using ExecutorType = TypeParam;
896+
ExecutorType executor;
897+
898+
auto node = std::make_shared<rclcpp::Node>("test_node");
899+
900+
bool timer1_works = false;
901+
bool timer2_works = false;
902+
903+
auto timer1 = node->create_timer(std::chrono::milliseconds(10), [&timer1_works]() {
904+
timer1_works = true;
905+
});
906+
auto timer2 = node->create_timer(std::chrono::milliseconds(10), [&timer2_works]() {
907+
timer2_works = true;
908+
});
909+
910+
executor.add_node(node);
911+
912+
// first let's make sure that both timers work
913+
auto max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
914+
while(!timer1_works || !timer2_works) {
915+
// let the executor pick up the node and the timers
916+
executor.spin_all(std::chrono::milliseconds(10));
917+
918+
const auto cur_time = std::chrono::steady_clock::now();
919+
ASSERT_LT(cur_time, max_end_time);
920+
}
921+
922+
// delete timer 2. Note, the executor uses an unordered map internally, to order
923+
// the entities added to the rcl waitset therefore the order is kind of undefined,
924+
// and this test may be flaky. In case it triggers, something is most likely
925+
// really broken.
926+
timer2.reset();
927+
928+
timer1_works = false;
929+
timer2_works = false;
930+
max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
931+
while(!timer1_works && !timer2_works) {
932+
// let the executor pick up the node and the timers
933+
executor.spin_all(std::chrono::milliseconds(10));
934+
935+
const auto cur_time = std::chrono::steady_clock::now();
936+
ASSERT_LT(cur_time, max_end_time);
937+
}
938+
939+
ASSERT_TRUE(timer1_works || timer2_works);
940+
}
941+
942+
TYPED_TEST(TestExecutors, dropSomeNodeWithTimer)
943+
{
944+
using ExecutorType = TypeParam;
945+
ExecutorType executor;
946+
947+
auto node1 = std::make_shared<rclcpp::Node>("test_node_1");
948+
auto node2 = std::make_shared<rclcpp::Node>("test_node_2");
949+
950+
bool timer1_works = false;
951+
bool timer2_works = false;
952+
953+
auto timer1 = node1->create_timer(std::chrono::milliseconds(10), [&timer1_works]() {
954+
timer1_works = true;
955+
});
956+
auto timer2 = node2->create_timer(std::chrono::milliseconds(10), [&timer2_works]() {
957+
timer2_works = true;
958+
});
959+
960+
executor.add_node(node1);
961+
executor.add_node(node2);
962+
963+
// first let's make sure that both timers work
964+
auto max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
965+
while(!timer1_works || !timer2_works) {
966+
// let the executor pick up the node and the timers
967+
executor.spin_all(std::chrono::milliseconds(10));
968+
969+
const auto cur_time = std::chrono::steady_clock::now();
970+
ASSERT_LT(cur_time, max_end_time);
971+
}
972+
973+
// delete node 1.
974+
node1 = nullptr;
975+
976+
timer2_works = false;
977+
max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
978+
while(!timer2_works) {
979+
// let the executor pick up the node and the timer
980+
executor.spin_all(std::chrono::milliseconds(10));
981+
982+
const auto cur_time = std::chrono::steady_clock::now();
983+
ASSERT_LT(cur_time, max_end_time);
984+
}
985+
986+
ASSERT_TRUE(timer2_works);
987+
}
988+
989+
TYPED_TEST(TestExecutors, dropSomeSubscription)
990+
{
991+
using ExecutorType = TypeParam;
992+
ExecutorType executor;
993+
994+
auto node = std::make_shared<rclcpp::Node>("test_node");
995+
996+
bool sub1_works = false;
997+
bool sub2_works = false;
998+
999+
auto sub1 = node->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
1000+
[&sub1_works](const test_msgs::msg::Empty &) {
1001+
sub1_works = true;
1002+
});
1003+
auto sub2 = node->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
1004+
[&sub2_works](const test_msgs::msg::Empty &) {
1005+
sub2_works = true;
1006+
});
1007+
1008+
auto pub = node->create_publisher<test_msgs::msg::Empty>("/test_drop", 10);
1009+
1010+
executor.add_node(node);
1011+
1012+
// first let's make sure that both timers work
1013+
auto max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
1014+
while(!sub1_works || !sub2_works) {
1015+
pub->publish(test_msgs::msg::Empty());
1016+
1017+
// let the executor pick up the node and the timers
1018+
executor.spin_all(std::chrono::milliseconds(10));
1019+
1020+
const auto cur_time = std::chrono::steady_clock::now();
1021+
ASSERT_LT(cur_time, max_end_time);
1022+
}
1023+
1024+
// delete subscription 2. Note, the executor uses an unordered map internally, to order
1025+
// the entities added to the rcl waitset therefore the order is kind of undefined,
1026+
// and this test may be flaky. In case it triggers, something is most likely
1027+
// really broken.
1028+
sub2.reset();
1029+
1030+
sub1_works = false;
1031+
sub2_works = false;
1032+
max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
1033+
while(!sub1_works && !sub2_works) {
1034+
pub->publish(test_msgs::msg::Empty());
1035+
1036+
// let the executor pick up the node and the timers
1037+
executor.spin_all(std::chrono::milliseconds(10));
1038+
1039+
const auto cur_time = std::chrono::steady_clock::now();
1040+
ASSERT_LT(cur_time, max_end_time);
1041+
}
1042+
1043+
ASSERT_TRUE(sub1_works || sub2_works);
1044+
}
1045+
1046+
TYPED_TEST(TestExecutors, dropSomeNodesWithSubscription)
1047+
{
1048+
using ExecutorType = TypeParam;
1049+
ExecutorType executor;
1050+
1051+
auto node = std::make_shared<rclcpp::Node>("test_node");
1052+
auto node1 = std::make_shared<rclcpp::Node>("test_node_1");
1053+
auto node2 = std::make_shared<rclcpp::Node>("test_node_2");
1054+
1055+
bool sub1_works = false;
1056+
bool sub2_works = false;
1057+
1058+
auto sub1 = node1->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
1059+
[&sub1_works](const test_msgs::msg::Empty &) {
1060+
sub1_works = true;
1061+
});
1062+
auto sub2 = node2->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
1063+
[&sub2_works](const test_msgs::msg::Empty &) {
1064+
sub2_works = true;
1065+
});
1066+
1067+
auto pub = node->create_publisher<test_msgs::msg::Empty>("/test_drop", 10);
1068+
1069+
executor.add_node(node);
1070+
executor.add_node(node1);
1071+
executor.add_node(node2);
1072+
1073+
// first let's make sure that both subscribers work
1074+
auto max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
1075+
while(!sub1_works || !sub2_works) {
1076+
pub->publish(test_msgs::msg::Empty());
1077+
1078+
// let the executor pick up the node and the timers
1079+
executor.spin_all(std::chrono::milliseconds(10));
1080+
1081+
const auto cur_time = std::chrono::steady_clock::now();
1082+
ASSERT_LT(cur_time, max_end_time);
1083+
}
1084+
1085+
// delete node 2.
1086+
node2 = nullptr;
1087+
1088+
sub1_works = false;
1089+
max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
1090+
while(!sub1_works) {
1091+
pub->publish(test_msgs::msg::Empty());
1092+
1093+
// let the executor pick up the node and the timers
1094+
executor.spin_all(std::chrono::milliseconds(10));
1095+
1096+
const auto cur_time = std::chrono::steady_clock::now();
1097+
ASSERT_LT(cur_time, max_end_time);
1098+
}
1099+
1100+
ASSERT_TRUE(sub1_works);
1101+
}

0 commit comments

Comments
 (0)