diff --git a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp index 8f8cd4ac896fe..e64411a66f521 100644 --- a/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp +++ b/evaluator/perception_online_evaluator/test/test_perception_online_evaluator_node.cpp @@ -77,11 +77,6 @@ class EvalTest : public ::testing::Test objects_pub_ = rclcpp::create_publisher( dummy_node, "/perception_online_evaluator/input/objects", 1); - marker_sub_ = rclcpp::create_subscription( - eval_node, "perception_online_evaluator/markers", 10, - [this]([[maybe_unused]] const MarkerArray::ConstSharedPtr msg) { - has_received_marker_ = true; - }); uuid_ = generateUUID(); } @@ -229,12 +224,10 @@ class EvalTest : public ::testing::Test void waitForDummyNode() { - // wait for the marker to be published - publishObjects(makeStraightPredictedObjects(0)); - while (!has_received_marker_) { + // Wait until the publisher is connected to the dummy node + while (objects_pub_->get_subscription_count() == 0) { rclcpp::spin_some(dummy_node); rclcpp::sleep_for(std::chrono::milliseconds(100)); - rclcpp::spin_some(eval_node); } } @@ -248,8 +241,6 @@ class EvalTest : public ::testing::Test // Pub/Sub rclcpp::Publisher::SharedPtr objects_pub_; rclcpp::Subscription::SharedPtr metric_sub_; - rclcpp::Subscription::SharedPtr marker_sub_; - bool has_received_marker_{false}; double time_delay_ = 5.0; double time_step_ = 0.5;