Skip to content

Commit 54b268d

Browse files
jmachowinskimergify[bot]
authored andcommitted
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]> (cherry picked from commit 605251b)
1 parent 2eaa2eb commit 54b268d

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
@@ -821,3 +821,213 @@ TYPED_TEST(TestExecutors, testRaceDropCallbackGroupFromSecondThread)
821821
executor.cancel();
822822
executor_thread.join();
823823
}
824+
825+
TYPED_TEST(TestExecutors, dropSomeTimer)
826+
{
827+
using ExecutorType = TypeParam;
828+
ExecutorType executor;
829+
830+
auto node = std::make_shared<rclcpp::Node>("test_node");
831+
832+
bool timer1_works = false;
833+
bool timer2_works = false;
834+
835+
auto timer1 = node->create_timer(std::chrono::milliseconds(10), [&timer1_works]() {
836+
timer1_works = true;
837+
});
838+
auto timer2 = node->create_timer(std::chrono::milliseconds(10), [&timer2_works]() {
839+
timer2_works = true;
840+
});
841+
842+
executor.add_node(node);
843+
844+
// first let's make sure that both timers work
845+
auto max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
846+
while(!timer1_works || !timer2_works) {
847+
// let the executor pick up the node and the timers
848+
executor.spin_all(std::chrono::milliseconds(10));
849+
850+
const auto cur_time = std::chrono::steady_clock::now();
851+
ASSERT_LT(cur_time, max_end_time);
852+
}
853+
854+
// delete timer 2. Note, the executor uses an unordered map internally, to order
855+
// the entities added to the rcl waitset therefore the order is kind of undefined,
856+
// and this test may be flaky. In case it triggers, something is most likely
857+
// really broken.
858+
timer2.reset();
859+
860+
timer1_works = false;
861+
timer2_works = false;
862+
max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
863+
while(!timer1_works && !timer2_works) {
864+
// let the executor pick up the node and the timers
865+
executor.spin_all(std::chrono::milliseconds(10));
866+
867+
const auto cur_time = std::chrono::steady_clock::now();
868+
ASSERT_LT(cur_time, max_end_time);
869+
}
870+
871+
ASSERT_TRUE(timer1_works || timer2_works);
872+
}
873+
874+
TYPED_TEST(TestExecutors, dropSomeNodeWithTimer)
875+
{
876+
using ExecutorType = TypeParam;
877+
ExecutorType executor;
878+
879+
auto node1 = std::make_shared<rclcpp::Node>("test_node_1");
880+
auto node2 = std::make_shared<rclcpp::Node>("test_node_2");
881+
882+
bool timer1_works = false;
883+
bool timer2_works = false;
884+
885+
auto timer1 = node1->create_timer(std::chrono::milliseconds(10), [&timer1_works]() {
886+
timer1_works = true;
887+
});
888+
auto timer2 = node2->create_timer(std::chrono::milliseconds(10), [&timer2_works]() {
889+
timer2_works = true;
890+
});
891+
892+
executor.add_node(node1);
893+
executor.add_node(node2);
894+
895+
// first let's make sure that both timers work
896+
auto max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
897+
while(!timer1_works || !timer2_works) {
898+
// let the executor pick up the node and the timers
899+
executor.spin_all(std::chrono::milliseconds(10));
900+
901+
const auto cur_time = std::chrono::steady_clock::now();
902+
ASSERT_LT(cur_time, max_end_time);
903+
}
904+
905+
// delete node 1.
906+
node1 = nullptr;
907+
908+
timer2_works = false;
909+
max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
910+
while(!timer2_works) {
911+
// let the executor pick up the node and the timer
912+
executor.spin_all(std::chrono::milliseconds(10));
913+
914+
const auto cur_time = std::chrono::steady_clock::now();
915+
ASSERT_LT(cur_time, max_end_time);
916+
}
917+
918+
ASSERT_TRUE(timer2_works);
919+
}
920+
921+
TYPED_TEST(TestExecutors, dropSomeSubscription)
922+
{
923+
using ExecutorType = TypeParam;
924+
ExecutorType executor;
925+
926+
auto node = std::make_shared<rclcpp::Node>("test_node");
927+
928+
bool sub1_works = false;
929+
bool sub2_works = false;
930+
931+
auto sub1 = node->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
932+
[&sub1_works](const test_msgs::msg::Empty &) {
933+
sub1_works = true;
934+
});
935+
auto sub2 = node->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
936+
[&sub2_works](const test_msgs::msg::Empty &) {
937+
sub2_works = true;
938+
});
939+
940+
auto pub = node->create_publisher<test_msgs::msg::Empty>("/test_drop", 10);
941+
942+
executor.add_node(node);
943+
944+
// first let's make sure that both timers work
945+
auto max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
946+
while(!sub1_works || !sub2_works) {
947+
pub->publish(test_msgs::msg::Empty());
948+
949+
// let the executor pick up the node and the timers
950+
executor.spin_all(std::chrono::milliseconds(10));
951+
952+
const auto cur_time = std::chrono::steady_clock::now();
953+
ASSERT_LT(cur_time, max_end_time);
954+
}
955+
956+
// delete subscription 2. Note, the executor uses an unordered map internally, to order
957+
// the entities added to the rcl waitset therefore the order is kind of undefined,
958+
// and this test may be flaky. In case it triggers, something is most likely
959+
// really broken.
960+
sub2.reset();
961+
962+
sub1_works = false;
963+
sub2_works = false;
964+
max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
965+
while(!sub1_works && !sub2_works) {
966+
pub->publish(test_msgs::msg::Empty());
967+
968+
// let the executor pick up the node and the timers
969+
executor.spin_all(std::chrono::milliseconds(10));
970+
971+
const auto cur_time = std::chrono::steady_clock::now();
972+
ASSERT_LT(cur_time, max_end_time);
973+
}
974+
975+
ASSERT_TRUE(sub1_works || sub2_works);
976+
}
977+
978+
TYPED_TEST(TestExecutors, dropSomeNodesWithSubscription)
979+
{
980+
using ExecutorType = TypeParam;
981+
ExecutorType executor;
982+
983+
auto node = std::make_shared<rclcpp::Node>("test_node");
984+
auto node1 = std::make_shared<rclcpp::Node>("test_node_1");
985+
auto node2 = std::make_shared<rclcpp::Node>("test_node_2");
986+
987+
bool sub1_works = false;
988+
bool sub2_works = false;
989+
990+
auto sub1 = node1->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
991+
[&sub1_works](const test_msgs::msg::Empty &) {
992+
sub1_works = true;
993+
});
994+
auto sub2 = node2->create_subscription<test_msgs::msg::Empty>("/test_drop", 10,
995+
[&sub2_works](const test_msgs::msg::Empty &) {
996+
sub2_works = true;
997+
});
998+
999+
auto pub = node->create_publisher<test_msgs::msg::Empty>("/test_drop", 10);
1000+
1001+
executor.add_node(node);
1002+
executor.add_node(node1);
1003+
executor.add_node(node2);
1004+
1005+
// first let's make sure that both subscribers work
1006+
auto max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
1007+
while(!sub1_works || !sub2_works) {
1008+
pub->publish(test_msgs::msg::Empty());
1009+
1010+
// let the executor pick up the node and the timers
1011+
executor.spin_all(std::chrono::milliseconds(10));
1012+
1013+
const auto cur_time = std::chrono::steady_clock::now();
1014+
ASSERT_LT(cur_time, max_end_time);
1015+
}
1016+
1017+
// delete node 2.
1018+
node2 = nullptr;
1019+
1020+
sub1_works = false;
1021+
max_end_time = std::chrono::steady_clock::now() + std::chrono::milliseconds(100);
1022+
while(!sub1_works) {
1023+
pub->publish(test_msgs::msg::Empty());
1024+
1025+
// let the executor pick up the node and the timers
1026+
executor.spin_all(std::chrono::milliseconds(10));
1027+
1028+
const auto cur_time = std::chrono::steady_clock::now();
1029+
ASSERT_LT(cur_time, max_end_time);
1030+
}
1031+
1032+
ASSERT_TRUE(sub1_works);
1033+
}

0 commit comments

Comments
 (0)