Skip to content

Commit

Permalink
feat(perception_online_evaluator): better waitForDummyNode (autowaref…
Browse files Browse the repository at this point in the history
  • Loading branch information
kosuke55 authored Apr 17, 2024
1 parent c40da9f commit 51efa6d
Showing 1 changed file with 2 additions and 11 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -77,11 +77,6 @@ class EvalTest : public ::testing::Test
objects_pub_ = rclcpp::create_publisher<PredictedObjects>(
dummy_node, "/perception_online_evaluator/input/objects", 1);

marker_sub_ = rclcpp::create_subscription<MarkerArray>(
eval_node, "perception_online_evaluator/markers", 10,
[this]([[maybe_unused]] const MarkerArray::ConstSharedPtr msg) {
has_received_marker_ = true;
});
uuid_ = generateUUID();
}

Expand Down Expand Up @@ -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);
}
}

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

double time_delay_ = 5.0;
double time_step_ = 0.5;
Expand Down

0 comments on commit 51efa6d

Please sign in to comment.