@@ -77,11 +77,6 @@ class EvalTest : public ::testing::Test
77
77
objects_pub_ = rclcpp::create_publisher<PredictedObjects>(
78
78
dummy_node, " /perception_online_evaluator/input/objects" , 1 );
79
79
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
- });
85
80
uuid_ = generateUUID ();
86
81
}
87
82
@@ -229,12 +224,10 @@ class EvalTest : public ::testing::Test
229
224
230
225
void waitForDummyNode ()
231
226
{
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 ) {
235
229
rclcpp::spin_some (dummy_node);
236
230
rclcpp::sleep_for (std::chrono::milliseconds (100 ));
237
- rclcpp::spin_some (eval_node);
238
231
}
239
232
}
240
233
@@ -248,8 +241,6 @@ class EvalTest : public ::testing::Test
248
241
// Pub/Sub
249
242
rclcpp::Publisher<PredictedObjects>::SharedPtr objects_pub_;
250
243
rclcpp::Subscription<DiagnosticArray>::SharedPtr metric_sub_;
251
- rclcpp::Subscription<MarkerArray>::SharedPtr marker_sub_;
252
- bool has_received_marker_{false };
253
244
254
245
double time_delay_ = 5.0 ;
255
246
double time_step_ = 0.5 ;
0 commit comments