Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Use a single reentrant callback group for all subscriptions #122

Merged
merged 1 commit into from
Dec 19, 2022
Merged
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
9 changes: 3 additions & 6 deletions ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -159,6 +159,7 @@ class FoxgloveBridge : public rclcpp::Node {
_rosgraphPollThread =
std::make_unique<std::thread>(std::bind(&FoxgloveBridge::rosgraphPollThread, this));

_subscriptionCallbackGroup = this->create_callback_group(rclcpp::CallbackGroupType::Reentrant);
_clientPublishCallbackGroup =
this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);

Expand Down Expand Up @@ -331,8 +332,8 @@ class FoxgloveBridge : public rclcpp::Node {
std::unordered_map<TopicAndDatatype, foxglove::Channel, PairHash> _advertisedTopics;
std::unordered_map<foxglove::ChannelId, TopicAndDatatype> _channelToTopicAndDatatype;
std::unordered_map<foxglove::ChannelId, SubscriptionsByClient> _subscriptions;
std::unordered_map<foxglove::ChannelId, rclcpp::CallbackGroup::SharedPtr> _channelCallbackGroups;
PublicationsByClient _clientAdvertisedTopics;
rclcpp::CallbackGroup::SharedPtr _subscriptionCallbackGroup;
rclcpp::CallbackGroup::SharedPtr _clientPublishCallbackGroup;
std::mutex _subscriptionsMutex;
std::mutex _clientAdvertisementsMutex;
Expand Down Expand Up @@ -377,13 +378,9 @@ class FoxgloveBridge : public rclcpp::Node {
topic.c_str(), datatype.c_str());
};

const auto& [callbackGroup, isNewlyInserted] = _channelCallbackGroups.insert(
{channelId, this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive)});
(void)isNewlyInserted;

rclcpp::SubscriptionOptions subscriptionOptions;
subscriptionOptions.event_callbacks = eventCallbacks;
subscriptionOptions.callback_group = callbackGroup->second;
subscriptionOptions.callback_group = _subscriptionCallbackGroup;

// Select an appropriate subscription QOS profile. This is similar to how ros2 topic echo
// does it:
Expand Down