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

Correctly handle multiple StaticTransformBroadcasters in a single process #455

Open
wants to merge 1 commit into
base: noetic-devel
Choose a base branch
from
Open
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
7 changes: 2 additions & 5 deletions tf2_ros/include/tf2_ros/static_transform_broadcaster.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@
namespace tf2_ros
{

struct StaticTransformBroadcasterImpl;

/** \brief This class provides an easy way to publish coordinate frame transform information.
* It will handle all the messaging and stuffing of messages. And the function prototypes lay out all the
Expand All @@ -63,11 +64,7 @@ class StaticTransformBroadcaster{
void sendTransform(const std::vector<geometry_msgs::TransformStamped> & transforms);

private:
/// Internal reference to ros::Node
ros::NodeHandle node_;
ros::Publisher publisher_;
tf2_msgs::TFMessage net_message_;

std::shared_ptr<StaticTransformBroadcasterImpl> impl_;
};

}
Expand Down
37 changes: 32 additions & 5 deletions tf2_ros/src/static_transform_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,37 @@
#include "tf2_msgs/TFMessage.h"
#include "tf2_ros/static_transform_broadcaster.h"
#include <algorithm>
#include <mutex>

namespace tf2_ros {

struct StaticTransformBroadcasterImpl {
ros::NodeHandle node_; // internal reference to node
ros::Publisher publisher_;
tf2_msgs::TFMessage net_message_; // message comprising all static transforms

StaticTransformBroadcasterImpl() {
publisher_ = node_.advertise<tf2_msgs::TFMessage>("/tf_static", 100, true);
}
StaticTransformBroadcasterImpl(const StaticTransformBroadcasterImpl& other) = delete;

static std::shared_ptr<StaticTransformBroadcasterImpl> getInstance() {
static std::mutex mutex;
static std::weak_ptr<StaticTransformBroadcasterImpl> singleton;

std::lock_guard<std::mutex> lock(mutex);
if (singleton.expired()) { // create a new instance if required
auto result = std::make_shared<StaticTransformBroadcasterImpl>();
singleton = result;
return result;
} // otherwise return existing one
return singleton.lock();
}
};

StaticTransformBroadcaster::StaticTransformBroadcaster()
{
publisher_ = node_.advertise<tf2_msgs::TFMessage>("/tf_static", 100, true);
impl_ = StaticTransformBroadcasterImpl::getInstance();
};

void StaticTransformBroadcaster::sendTransform(const std::vector<geometry_msgs::TransformStamped> & msgtf)
Expand All @@ -50,15 +75,17 @@ void StaticTransformBroadcaster::sendTransform(const std::vector<geometry_msgs::
auto predicate = [&input](const geometry_msgs::TransformStamped existing) {
return input.child_frame_id == existing.child_frame_id;
};
auto existing = std::find_if(net_message_.transforms.begin(), net_message_.transforms.end(), predicate);

if (existing != net_message_.transforms.end())
auto& transforms = impl_->net_message_.transforms;
auto existing = std::find_if(transforms.begin(), transforms.end(), predicate);

if (existing != transforms.end())
*existing = input;
else
net_message_.transforms.push_back(input);
transforms.push_back(input);
}

publisher_.publish(net_message_);
impl_->publisher_.publish(impl_->net_message_);
}

}