Skip to content

[JSB] skip publish on no subscription #1609

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

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
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
9 changes: 7 additions & 2 deletions joint_state_broadcaster/src/joint_state_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -360,7 +360,9 @@ controller_interface::return_type JointStateBroadcaster::update(
state_interface.get_value());
}

if (realtime_joint_state_publisher_ && realtime_joint_state_publisher_->trylock())
if (
realtime_joint_state_publisher_ && joint_state_publisher_->get_subscription_count() > 0u &&
Copy link

Choose a reason for hiding this comment

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

looks good. Are the rmw and implementations thereof doing this implicitly already?

Copy link
Member Author

Choose a reason for hiding this comment

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

I believe yes

Copy link

Choose a reason for hiding this comment

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

meaning subscription count is polled outside the RT loop where it is definitely safe, right? To my best understanding, the publish operation just appends a buffer

Copy link
Member Author

@saikishor saikishor Apr 4, 2025

Choose a reason for hiding this comment

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

Yes! That's what I understood

realtime_joint_state_publisher_->trylock())
{
auto & joint_state_msg = realtime_joint_state_publisher_->msg_;

Expand All @@ -378,7 +380,10 @@ controller_interface::return_type JointStateBroadcaster::update(
realtime_joint_state_publisher_->unlockAndPublish();
}

if (realtime_dynamic_joint_state_publisher_ && realtime_dynamic_joint_state_publisher_->trylock())
if (
realtime_dynamic_joint_state_publisher_ &&
dynamic_joint_state_publisher_->get_subscription_count() > 0u &&
realtime_dynamic_joint_state_publisher_->trylock())
{
auto & dynamic_joint_state_msg = realtime_dynamic_joint_state_publisher_->msg_;
dynamic_joint_state_msg.header.stamp = time;
Expand Down