From cf918336a078ed183a90c04f3d14171696523f6e Mon Sep 17 00:00:00 2001 From: Seki Inoue Date: Wed, 5 Oct 2022 14:19:42 +0900 Subject: [PATCH 1/2] cache rosparam tf_prefix --- include/robot_state_publisher/joint_state_listener.h | 3 ++- src/joint_state_listener.cpp | 12 ++++++++---- 2 files changed, 10 insertions(+), 5 deletions(-) diff --git a/include/robot_state_publisher/joint_state_listener.h b/include/robot_state_publisher/joint_state_listener.h index ee03951..7638b87 100644 --- a/include/robot_state_publisher/joint_state_listener.h +++ b/include/robot_state_publisher/joint_state_listener.h @@ -87,7 +87,8 @@ class JointStateListener { MimicMap mimic_; bool use_tf_static_; bool ignore_timestamp_; - + std::string tf_prefix_; + bool tf_prefix_cached_; }; } diff --git a/src/joint_state_listener.cpp b/src/joint_state_listener.cpp index c89fede..135ee3e 100644 --- a/src/joint_state_listener.cpp +++ b/src/joint_state_listener.cpp @@ -58,7 +58,7 @@ JointStateListener::JointStateListener(const KDL::Tree& tree, const MimicMap& m, } JointStateListener::JointStateListener(const std::shared_ptr& rsp, const MimicMap& m) - : state_publisher_(rsp), mimic_(m) + : state_publisher_(rsp), mimic_(m), tf_prefix_cached_(false) { ros::NodeHandle n_tilde("~"); ros::NodeHandle n; @@ -92,15 +92,19 @@ JointStateListener::~JointStateListener() std::string JointStateListener::getTFPrefix() { + if (tf_prefix_cached_) { + return tf_prefix_; + } + ros::NodeHandle n_tilde("~"); - std::string tf_prefix; // 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("")); + n_tilde.param(tf_prefix_key, tf_prefix_, std::string("")); + tf_prefix_cached_ = true; - return tf_prefix; + return tf_prefix_; } void JointStateListener::callbackFixedJoint(const ros::TimerEvent& e) From c0275b1596a0571b1228a5e3248a070163cdbd4c Mon Sep 17 00:00:00 2001 From: Seki Inoue Date: Thu, 13 Oct 2022 22:38:02 +0900 Subject: [PATCH 2/2] ABI-safe tf_prefix cache --- .../joint_state_listener.h | 3 +- src/joint_state_listener.cpp | 50 ++++++++++++++++--- 2 files changed, 44 insertions(+), 9 deletions(-) diff --git a/include/robot_state_publisher/joint_state_listener.h b/include/robot_state_publisher/joint_state_listener.h index 7638b87..ee03951 100644 --- a/include/robot_state_publisher/joint_state_listener.h +++ b/include/robot_state_publisher/joint_state_listener.h @@ -87,8 +87,7 @@ class JointStateListener { MimicMap mimic_; bool use_tf_static_; bool ignore_timestamp_; - std::string tf_prefix_; - bool tf_prefix_cached_; + }; } diff --git a/src/joint_state_listener.cpp b/src/joint_state_listener.cpp index 135ee3e..84e562b 100644 --- a/src/joint_state_listener.cpp +++ b/src/joint_state_listener.cpp @@ -36,7 +36,9 @@ #include #include +#include #include +#include #include #include @@ -48,6 +50,37 @@ using namespace robot_state_publisher; +namespace robot_state_publisher { + +template +class ParameterCache { +public: + void set(const void* owner, const T& value) + { + std::lock_guard lock(mtx_); + store_[owner] = value; + } + bool get(const void* owner, T& value) + { + std::lock_guard lock(mtx_); + if (store_.count(owner) > 0) { + value = store_.at(owner); + return true; + } + return false; + } + void clear(const void* owner) + { + std::lock_guard lock(mtx_); + store_.erase(owner); + } +private: + std::mutex mtx_; // shared_mutex is preferable + std::unordered_map store_; +}; +ParameterCache g_tf_prefix_cache; +} + JointStateListener::JointStateListener() : JointStateListener(KDL::Tree(), MimicMap()) { } @@ -58,7 +91,7 @@ JointStateListener::JointStateListener(const KDL::Tree& tree, const MimicMap& m, } JointStateListener::JointStateListener(const std::shared_ptr& 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; @@ -88,12 +121,15 @@ JointStateListener::JointStateListener(const std::shared_ptr