Thanks to visit codestin.com
Credit goes to github.com

Skip to content

Move pub_rviz_markers_ to it's own callback queue #193

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

Merged
merged 1 commit into from
Oct 5, 2022

Conversation

jspricke
Copy link
Contributor

@jspricke jspricke commented Aug 2, 2021

waitForSubscriber used to call ros::spinOnce() which could trigger
callbacks from other topics in other threads. In case those have a lock
to only get called once, this would look the visual_tools thread.

Closes: #146

waitForSubscriber used to call ros::spinOnce() which could trigger
callbacks from other topics in other threads. In case those have a lock
to only get called once, this would look the visual_tools thread.

Closes: PickNikRobotics#146
@jspricke
Copy link
Contributor Author

jspricke commented Aug 2, 2021

You probably want the same here:

ros::spinOnce();
not sure.

@jspricke
Copy link
Contributor Author

jspricke commented Aug 2, 2021

This is an ABI break, btw.

@@ -280,7 +280,9 @@ void RvizVisualTools::loadMarkerPub(bool wait_for_subscriber, bool latched)
}

// Rviz marker publisher
pub_rviz_markers_ = nh_.advertise<visualization_msgs::MarkerArray>(marker_topic_, 10, latched);
ros::NodeHandle nh(nh_.getNamespace());
nh.setCallbackQueue(&vis_marker_queue_);
Copy link
Contributor

Choose a reason for hiding this comment

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

A comment on why this is being done would be great

@@ -334,7 +336,7 @@ bool RvizVisualTools::waitForSubscriber(const ros::Publisher& pub, double wait_t
"will be lost.");
return false;
}
ros::spinOnce();
vis_marker_queue_.callAvailable(ros::WallDuration());
Copy link
Contributor

Choose a reason for hiding this comment

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

Your change looks good. It makes sense to me.

But, did you try deleting ros::spinOnce() completely? There might not be any noticeable downside and that is the simpler fix.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Well the code tries to block until there is a subscriber so deleting it would result in a different behavior.
But I just bumped into this again when using ros::spin() and there PR didn't help so I think it would be better to drop this or provide a non blocking interface. I can come up with a patch if more people agree.

Copy link
Member

Choose a reason for hiding this comment

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

I added this function because often important stuff was published to Rviz before Rviz was done loading, and the visualizations would not work correctly. It was great for demo / testing code, not sure its useful in a production env though. Maybe just warn API users not to use this function in production systems

Copy link
Contributor Author

Choose a reason for hiding this comment

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

but is there a way to make it work without calling this function? I guess one could take the markers_ and do the publish manually but that sounds wrong, or set pub_rviz_markers_connected_ and pub_rviz_markers_waited_ to true..
Maybe we could add a variable to the constructor to disable the connection check or have a trigger variant to not do it. Honestly I think the check should be disabled by default. What do you think?

Copy link
Contributor

Choose a reason for hiding this comment

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

I just verified in a small C++ test script that spinning is fully independent of node connection handling and I would have been surprised by anything else.
So even if you don't spin, getNumSubscribers reports new subscribers as well.

@jspricke From all that I can see the change in behavior you refer to actually means fixing the bug.
The method is not supposed to spin any queue. It's supposed to wait and poll*.

-- Slightly off-topic

    • I was convinced there is an API somewhere to get notified about new subscribes/unsubscribes and that would be even better. But I can't seem to find it

@@ -280,7 +280,9 @@ void RvizVisualTools::loadMarkerPub(bool wait_for_subscriber, bool latched)
}

// Rviz marker publisher
pub_rviz_markers_ = nh_.advertise<visualization_msgs::MarkerArray>(marker_topic_, 10, latched);
ros::NodeHandle nh(nh_.getNamespace());
Copy link
Member

Choose a reason for hiding this comment

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

can you make this nh var name more descriptive, so its clear how its diff than nh_?

@@ -334,7 +336,7 @@ bool RvizVisualTools::waitForSubscriber(const ros::Publisher& pub, double wait_t
"will be lost.");
return false;
}
ros::spinOnce();
vis_marker_queue_.callAvailable(ros::WallDuration());
Copy link
Member

Choose a reason for hiding this comment

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

I added this function because often important stuff was published to Rviz before Rviz was done loading, and the visualizations would not work correctly. It was great for demo / testing code, not sure its useful in a production env though. Maybe just warn API users not to use this function in production systems

Copy link
Contributor

@v4hn v4hn left a comment

Choose a reason for hiding this comment

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

This is the alternative approach to #224 . They solve the same problem in different classes.
I believe either approach is fine and these issues should be fixed upstream.

@tylerjw got a minute?

@jspricke jspricke closed this Sep 26, 2022
@jspricke jspricke deleted the fix_deadlock branch September 26, 2022 11:49
@jspricke jspricke restored the fix_deadlock branch September 27, 2022 07:49
@jspricke jspricke reopened this Sep 27, 2022
@codecov
Copy link

codecov bot commented Sep 27, 2022

Codecov Report

❗ No coverage uploaded for pull request base (master@99e8c9c). Click here to learn what that means.
The diff coverage is n/a.

@@            Coverage Diff            @@
##             master     #193   +/-   ##
=========================================
  Coverage          ?   19.78%           
=========================================
  Files             ?        5           
  Lines             ?     1703           
  Branches          ?        0           
=========================================
  Hits              ?      337           
  Misses            ?     1366           
  Partials          ?        0           

📣 We’re building smart automated test selection to slash your CI/CD build times. Learn more

Copy link
Collaborator

@JafarAbdi JafarAbdi left a comment

Choose a reason for hiding this comment

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

LGTM, I like the AsyncSpinner approach more, though :D

@JafarAbdi JafarAbdi merged commit 74b92d8 into PickNikRobotics:master Oct 5, 2022
@JafarAbdi
Copy link
Collaborator

After 13 months 😿

@jspricke jspricke deleted the fix_deadlock branch October 5, 2022 16:02
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

trigger() blocks forever - bug?
5 participants