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

Commit

Permalink
Merge pull request #2 from peroxyacyl/2022.10.13-cache-tf-prefix-abi
Browse files Browse the repository at this point in the history
  • Loading branch information
peroxyacyl authored Oct 24, 2022
2 parents 105a476 + c0275b1 commit d6db7b6
Show file tree
Hide file tree
Showing 2 changed files with 44 additions and 9 deletions.
3 changes: 1 addition & 2 deletions include/robot_state_publisher/joint_state_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,8 +87,7 @@ class JointStateListener {
MimicMap mimic_;
bool use_tf_static_;
bool ignore_timestamp_;
std::string tf_prefix_;
bool tf_prefix_cached_;

};
}

Expand Down
50 changes: 43 additions & 7 deletions src/joint_state_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,9 @@

#include <algorithm>
#include <map>
#include <mutex>
#include <string>
#include <unordered_map>

#include <ros/ros.h>
#include <urdf/model.h>
Expand All @@ -48,6 +50,37 @@

using namespace robot_state_publisher;

namespace robot_state_publisher {

template <typename T>
class ParameterCache {
public:
void set(const void* owner, const T& value)
{
std::lock_guard<std::mutex> lock(mtx_);
store_[owner] = value;
}
bool get(const void* owner, T& value)
{
std::lock_guard<std::mutex> lock(mtx_);
if (store_.count(owner) > 0) {
value = store_.at(owner);
return true;
}
return false;
}
void clear(const void* owner)
{
std::lock_guard<std::mutex> lock(mtx_);
store_.erase(owner);
}
private:
std::mutex mtx_; // shared_mutex is preferable
std::unordered_map<const void*, T> store_;
};
ParameterCache<std::string> g_tf_prefix_cache;
}

JointStateListener::JointStateListener() : JointStateListener(KDL::Tree(), MimicMap())
{
}
Expand All @@ -58,7 +91,7 @@ JointStateListener::JointStateListener(const KDL::Tree& tree, const MimicMap& m,
}

JointStateListener::JointStateListener(const std::shared_ptr<RobotStatePublisher>& rsp, const MimicMap& m)
: state_publisher_(rsp), mimic_(m), tf_prefix_cached_(false)
: state_publisher_(rsp), mimic_(m)
{
ros::NodeHandle n_tilde("~");
ros::NodeHandle n;
Expand Down Expand Up @@ -88,23 +121,26 @@ JointStateListener::JointStateListener(const std::shared_ptr<RobotStatePublisher


JointStateListener::~JointStateListener()
{}
{
g_tf_prefix_cache.clear(this);
}

std::string JointStateListener::getTFPrefix()
{
if (tf_prefix_cached_) {
return tf_prefix_;
std::string tf_prefix;
if (g_tf_prefix_cache.get(this, tf_prefix)) {
return tf_prefix;
}

ros::NodeHandle n_tilde("~");

// get the tf_prefix parameter from the closest namespace
std::string tf_prefix_key;
n_tilde.searchParam("tf_prefix", tf_prefix_key);
n_tilde.param(tf_prefix_key, tf_prefix_, std::string(""));
tf_prefix_cached_ = true;
n_tilde.param(tf_prefix_key, tf_prefix, std::string(""));
g_tf_prefix_cache.set(this, tf_prefix);

return tf_prefix_;
return tf_prefix;
}

void JointStateListener::callbackFixedJoint(const ros::TimerEvent& e)
Expand Down

0 comments on commit d6db7b6

Please sign in to comment.