Skip to content
This repository is currently being migrated. It's locked while the migration is in progress.

Commit c0275b1

Browse files
committed
ABI-safe tf_prefix cache
1 parent cf91833 commit c0275b1

File tree

2 files changed

+44
-9
lines changed

2 files changed

+44
-9
lines changed

include/robot_state_publisher/joint_state_listener.h

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -87,8 +87,7 @@ class JointStateListener {
8787
MimicMap mimic_;
8888
bool use_tf_static_;
8989
bool ignore_timestamp_;
90-
std::string tf_prefix_;
91-
bool tf_prefix_cached_;
90+
9291
};
9392
}
9493

src/joint_state_listener.cpp

Lines changed: 43 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,9 @@
3636

3737
#include <algorithm>
3838
#include <map>
39+
#include <mutex>
3940
#include <string>
41+
#include <unordered_map>
4042

4143
#include <ros/ros.h>
4244
#include <urdf/model.h>
@@ -48,6 +50,37 @@
4850

4951
using namespace robot_state_publisher;
5052

53+
namespace robot_state_publisher {
54+
55+
template <typename T>
56+
class ParameterCache {
57+
public:
58+
void set(const void* owner, const T& value)
59+
{
60+
std::lock_guard<std::mutex> lock(mtx_);
61+
store_[owner] = value;
62+
}
63+
bool get(const void* owner, T& value)
64+
{
65+
std::lock_guard<std::mutex> lock(mtx_);
66+
if (store_.count(owner) > 0) {
67+
value = store_.at(owner);
68+
return true;
69+
}
70+
return false;
71+
}
72+
void clear(const void* owner)
73+
{
74+
std::lock_guard<std::mutex> lock(mtx_);
75+
store_.erase(owner);
76+
}
77+
private:
78+
std::mutex mtx_; // shared_mutex is preferable
79+
std::unordered_map<const void*, T> store_;
80+
};
81+
ParameterCache<std::string> g_tf_prefix_cache;
82+
}
83+
5184
JointStateListener::JointStateListener() : JointStateListener(KDL::Tree(), MimicMap())
5285
{
5386
}
@@ -58,7 +91,7 @@ JointStateListener::JointStateListener(const KDL::Tree& tree, const MimicMap& m,
5891
}
5992

6093
JointStateListener::JointStateListener(const std::shared_ptr<RobotStatePublisher>& rsp, const MimicMap& m)
61-
: state_publisher_(rsp), mimic_(m), tf_prefix_cached_(false)
94+
: state_publisher_(rsp), mimic_(m)
6295
{
6396
ros::NodeHandle n_tilde("~");
6497
ros::NodeHandle n;
@@ -88,23 +121,26 @@ JointStateListener::JointStateListener(const std::shared_ptr<RobotStatePublisher
88121

89122

90123
JointStateListener::~JointStateListener()
91-
{}
124+
{
125+
g_tf_prefix_cache.clear(this);
126+
}
92127

93128
std::string JointStateListener::getTFPrefix()
94129
{
95-
if (tf_prefix_cached_) {
96-
return tf_prefix_;
130+
std::string tf_prefix;
131+
if (g_tf_prefix_cache.get(this, tf_prefix)) {
132+
return tf_prefix;
97133
}
98134

99135
ros::NodeHandle n_tilde("~");
100136

101137
// get the tf_prefix parameter from the closest namespace
102138
std::string tf_prefix_key;
103139
n_tilde.searchParam("tf_prefix", tf_prefix_key);
104-
n_tilde.param(tf_prefix_key, tf_prefix_, std::string(""));
105-
tf_prefix_cached_ = true;
140+
n_tilde.param(tf_prefix_key, tf_prefix, std::string(""));
141+
g_tf_prefix_cache.set(this, tf_prefix);
106142

107-
return tf_prefix_;
143+
return tf_prefix;
108144
}
109145

110146
void JointStateListener::callbackFixedJoint(const ros::TimerEvent& e)

0 commit comments

Comments
 (0)