Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -79,8 +79,9 @@ class SubscriptionManager
{
return async(
std::launch::async, [this]() {
while (continue_spinning(expected_topics_with_size_)) {
rclcpp::spin_some(subscriber_node_);
rclcpp::executors::SingleThreadedExecutor exec;
while (rclcpp::ok() && continue_spinning(expected_topics_with_size_)) {
exec.spin_node_some(subscriber_node_);
}
});
}
Expand Down
1 change: 1 addition & 0 deletions rosbag2_transport/test/rosbag2_transport/test_play.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -446,6 +446,7 @@ class RosBag2PlayQosOverrideTestFixture : public RosBag2PlayTestFixture
} else {
EXPECT_NE(result, std::future_status::timeout);
}
// Have to rclcpp::shutdown here to make the spin_subscriptions async thread exit
transport.shutdown();
}

Expand Down
11 changes: 8 additions & 3 deletions rosbag2_transport/test/rosbag2_transport/test_record.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,9 +151,14 @@ TEST_F(RecordIntegrationTestFixture, receives_latched_messages)
// Publish messages before starting recording
test_msgs::msg::Strings msg;
msg.string_value = "Hello";
for (size_t i = 0; i < num_latched_messages; i++) {
publisher_transient_local->publish(msg);
rclcpp::spin_some(publisher_node);
{
// Scope the executor so that the node is removed from it before `spin_and_wait_for`
rclcpp::executors::SingleThreadedExecutor exec;
exec.add_node(publisher_node);
for (size_t i = 0; i < num_latched_messages; i++) {
publisher_transient_local->publish(msg);
exec.spin_some();
}
}
start_recording({false, false, {topic}, "rmw_format", 100ms});
auto & writer = static_cast<MockSequentialWriter &>(writer_->get_implementation_handle());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ class RosBag2NodeFixture : public Test
publisher_node_ = std::make_shared<rclcpp::Node>(
"publisher_node",
rclcpp::NodeOptions().start_parameter_event_publisher(false));
executor_.add_node(node_);
}

static void SetUpTestCase()
Expand Down Expand Up @@ -84,7 +85,7 @@ class RosBag2NodeFixture : public Test
});

while (counter < expected_messages_number) {
rclcpp::spin_some(node_);
executor_.spin_some();
}
return messages;
}
Expand All @@ -111,13 +112,14 @@ class RosBag2NodeFixture : public Test
if ((clock::now() - start) > timeout) {
return false;
}
rclcpp::spin_some(node_);
executor_.spin_some();
}
return true;
}

MemoryManagement memory_management_;
std::shared_ptr<rosbag2_transport::Rosbag2Node> node_;
rclcpp::executors::SingleThreadedExecutor executor_;
rclcpp::Node::SharedPtr publisher_node_;
std::vector<std::shared_ptr<rclcpp::PublisherBase>> publishers_;
};
Expand Down