Skip to content

Commit

Permalink
Do not use rclcpp::spin_some in tight loops as it makes the context s…
Browse files Browse the repository at this point in the history
…hutdown_callbacks huge, sometimes triggers bad_function on shutdown

Signed-off-by: Emerson Knapp <[email protected]>
  • Loading branch information
Emerson Knapp committed Apr 1, 2021
1 parent 2f30a78 commit ce4c324
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -77,10 +77,12 @@ class SubscriptionManager

std::future<void> spin_subscriptions()
{
rclcpp::executors::SingleThreadedExecutor exec;
exec.add_node(subscriber_node_);
return async(
std::launch::async, [this]() {
std::launch::async, [this, &exec]() {
while (continue_spinning(expected_topics_with_size_)) {
rclcpp::spin_some(subscriber_node_);
exec.spin_some();
}
});
}
Expand Down
4 changes: 3 additions & 1 deletion rosbag2_transport/test/rosbag2_transport/test_record.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,9 +151,11 @@ TEST_F(RecordIntegrationTestFixture, receives_latched_messages)
// Publish messages before starting recording
test_msgs::msg::Strings msg;
msg.string_value = "Hello";
rclcpp::executors::SingleThreadedExecutor exec;
exec.add_node(publisher_node);
for (size_t i = 0; i < num_latched_messages; i++) {
publisher_transient_local->publish(msg);
rclcpp::spin_some(publisher_node);
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 @@ -83,8 +83,10 @@ class RosBag2NodeFixture : public Test
counter++;
});

rclcpp::executors::SingleThreadedExecutor exec;
exec.add_node(node_);
while (counter < expected_messages_number) {
rclcpp::spin_some(node_);
exec.spin_some();
}
return messages;
}
Expand Down

0 comments on commit ce4c324

Please sign in to comment.