Skip to content

Commit 51efa6d

Browse files
authored
feat(perception_online_evaluator): better waitForDummyNode (autowarefoundation#6827)
1 parent c40da9f commit 51efa6d

File tree

1 file changed

+2
-11
lines changed

1 file changed

+2
-11
lines changed

evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp

+2-11
Original file line numberDiff line numberDiff line change
@@ -77,11 +77,6 @@ class EvalTest : public ::testing::Test
7777
objects_pub_ = rclcpp::create_publisher<PredictedObjects>(
7878
dummy_node, "/perception_online_evaluator/input/objects", 1);
7979

80-
marker_sub_ = rclcpp::create_subscription<MarkerArray>(
81-
eval_node, "perception_online_evaluator/markers", 10,
82-
[this]([[maybe_unused]] const MarkerArray::ConstSharedPtr msg) {
83-
has_received_marker_ = true;
84-
});
8580
uuid_ = generateUUID();
8681
}
8782

@@ -229,12 +224,10 @@ class EvalTest : public ::testing::Test
229224

230225
void waitForDummyNode()
231226
{
232-
// wait for the marker to be published
233-
publishObjects(makeStraightPredictedObjects(0));
234-
while (!has_received_marker_) {
227+
// Wait until the publisher is connected to the dummy node
228+
while (objects_pub_->get_subscription_count() == 0) {
235229
rclcpp::spin_some(dummy_node);
236230
rclcpp::sleep_for(std::chrono::milliseconds(100));
237-
rclcpp::spin_some(eval_node);
238231
}
239232
}
240233

@@ -248,8 +241,6 @@ class EvalTest : public ::testing::Test
248241
// Pub/Sub
249242
rclcpp::Publisher<PredictedObjects>::SharedPtr objects_pub_;
250243
rclcpp::Subscription<DiagnosticArray>::SharedPtr metric_sub_;
251-
rclcpp::Subscription<MarkerArray>::SharedPtr marker_sub_;
252-
bool has_received_marker_{false};
253244

254245
double time_delay_ = 5.0;
255246
double time_step_ = 0.5;

0 commit comments

Comments
 (0)