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

cache tf_prefix #201

Open
wants to merge 2 commits into
base: noetic-devel
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 1 commit
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
3 changes: 2 additions & 1 deletion include/robot_state_publisher/joint_state_listener.h
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,8 @@ class JointStateListener {
MimicMap mimic_;
bool use_tf_static_;
bool ignore_timestamp_;

std::string tf_prefix_;
bool tf_prefix_cached_;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Adding these members changes the size of the class, and that breaks ABI. This will have to be stored somewhere else so we can release it into Noetic.

One solution I've seen is to create a static global map in the .cpp file where the key is the this pointer, and the value is the things we want to store per class instance.

Copy link
Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you for your quick review!
I've put a minimal thread-safe map and stored (this, tf_prefix) in the callback. The entry is deleted in the destructor.

};
}

Expand Down
12 changes: 8 additions & 4 deletions src/joint_state_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,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)
: state_publisher_(rsp), mimic_(m), tf_prefix_cached_(false)
{
ros::NodeHandle n_tilde("~");
ros::NodeHandle n;
Expand Down Expand Up @@ -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)
Expand Down