Skip to content

Commit

Permalink
Avoid destruction of callback group when client channel is unadvertis…
Browse files Browse the repository at this point in the history
…ed (#109)

**Public-Facing Changes**
None 

**Description**
Destruction of callback groups seems to have undesired side effects (see
ros2/rclcpp#2053) so we have to keep them as
class members. In #92 we did that already for Subscriptions, but we
forgot to do that also for Publications.
  • Loading branch information
achim-k committed Dec 11, 2022
1 parent be99da4 commit b8ad4d5
Showing 1 changed file with 9 additions and 7 deletions.
16 changes: 9 additions & 7 deletions ros2_foxglove_bridge/src/ros2_foxglove_bridge.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ using namespace std::placeholders;
using LogLevel = foxglove::WebSocketLogLevel;
using Subscription = rclcpp::GenericSubscription::SharedPtr;
using SubscriptionsByClient = std::map<foxglove::ConnHandle, Subscription, std::owner_less<>>;
using Publication = std::pair<rclcpp::GenericPublisher::SharedPtr, rclcpp::PublisherOptions>;
using Publication = rclcpp::GenericPublisher::SharedPtr;
using ClientPublications = std::unordered_map<foxglove::ClientChannelId, Publication>;
using PublicationsByClient = std::map<foxglove::ConnHandle, ClientPublications, std::owner_less<>>;

Expand Down Expand Up @@ -151,6 +151,9 @@ class FoxgloveBridge : public rclcpp::Node {
// Start the thread polling for rosgraph changes
_rosgraphPollThread =
std::make_unique<std::thread>(std::bind(&FoxgloveBridge::rosgraphPollThread, this));

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

~FoxgloveBridge() {
Expand Down Expand Up @@ -334,6 +337,7 @@ class FoxgloveBridge : public rclcpp::Node {
std::unordered_map<foxglove::ChannelId, SubscriptionsByClient> _subscriptions;
std::unordered_map<foxglove::ChannelId, rclcpp::CallbackGroup::SharedPtr> _channelCallbackGroups;
PublicationsByClient _clientAdvertisedTopics;
rclcpp::CallbackGroup::SharedPtr _clientPublishCallbackGroup;
std::mutex _subscriptionsMutex;
std::mutex _clientAdvertisementsMutex;
std::unique_ptr<std::thread> _rosgraphPollThread;
Expand Down Expand Up @@ -526,17 +530,15 @@ class FoxgloveBridge : public rclcpp::Node {
const auto& topicType = advertisement.schemaName;
rclcpp::QoS qos{rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_default)};
rclcpp::PublisherOptions publisherOptions{};
publisherOptions.callback_group =
this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive);
publisherOptions.callback_group = _clientPublishCallbackGroup;
auto publisher = this->create_generic_publisher(topicName, topicType, qos, publisherOptions);

RCLCPP_INFO(this->get_logger(), "Client %s is advertising \"%s\" (%s) on channel %d",
_server->remoteEndpointString(hdl).c_str(), topicName.c_str(), topicType.c_str(),
advertisement.channelId);

// Store the new topic advertisement
auto publication = std::make_pair(publisher, publisherOptions);
clientPublications.emplace(advertisement.channelId, std::move(publication));
clientPublications.emplace(advertisement.channelId, std::move(publisher));
}

void clientUnadvertiseHandler(foxglove::ChannelId channelId, foxglove::ConnHandle hdl) {
Expand All @@ -561,7 +563,7 @@ class FoxgloveBridge : public rclcpp::Node {
return;
}

const auto& publisher = it2->second.first;
const auto& publisher = it2->second;
RCLCPP_INFO(this->get_logger(),
"Client %s is no longer advertising %s (%zu subscribers) on channel %d",
_server->remoteEndpointString(hdl).c_str(), publisher->get_topic_name(),
Expand Down Expand Up @@ -599,7 +601,7 @@ class FoxgloveBridge : public rclcpp::Node {
clientPublications.size());
return;
}
publisher = it2->second.first;
publisher = it2->second;
}

// Copy the message payload into a SerializedMessage object
Expand Down

0 comments on commit b8ad4d5

Please sign in to comment.