Skip to content
This repository was archived by the owner on May 31, 2025. It is now read-only.

rosbag play: added option wait-for-subscriber#959

Merged
dirk-thomas merged 4 commits intoros:kinetic-develfrom
cwecht:feature_rosbag_wait_for_subscriber
Jan 17, 2017
Merged

rosbag play: added option wait-for-subscriber#959
dirk-thomas merged 4 commits intoros:kinetic-develfrom
cwecht:feature_rosbag_wait_for_subscriber

Conversation

@cwecht
Copy link
Copy Markdown
Contributor

@cwecht cwecht commented Jan 12, 2017

Added an option --wait-for-subscriber. If this option is chosen, rosbag play will wait before publishing until every topic has at least one subscriber. This is pretty useful in tests using rostest if one wants to make sure that no message is dropped because of missing subscribers.

("pause-topics", po::value< std::vector<std::string> >()->multitoken(), "topics to pause playback on")
("bags", po::value< std::vector<std::string> >(), "bag files to play back from");
("bags", po::value< std::vector<std::string> >(), "bag files to play back from")
("wait-for-subscribers", "wait for subscribers before publishing");
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

Maybe update the text to wait for at least one subscriber on each topic before publishing to make the condition clearer to the user.

Same for the Python help text.

foreach(const value_type& pub, publishers_) {
all_topics_subscribed &= pub.second.getNumSubscribers() > 0;
}
}
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

Is this loop busy waiting? If yes, something less resource intensive might be good.

std::cout << "Waiting for subscribers." << std::endl;
while (!all_topics_subscribed) {
all_topics_subscribed = true;
typedef std::pair<std::string, ros::Publisher> value_type;
Copy link
Copy Markdown
Member

Choose a reason for hiding this comment

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

Might be cleaner to typedef std::map<std::string, ros::Publisher> PublisherMap in the header, and then here you can use PublisherMap::value_type directly in the for loop without needing this duplicated definition.

@dirk-thomas
Copy link
Copy Markdown
Member

Thank you for the contribution!

@dirk-thomas dirk-thomas merged commit a6f3271 into ros:kinetic-devel Jan 17, 2017
ggallagher01 pushed a commit to clearpathrobotics/ros_comm that referenced this pull request Jan 26, 2017
* rosbag play: added option wait-for-subscriber

* rosbag play: improved help-text of wait-for-subscribers-option

* rosbag play: added typedef PublisherMap

* rosbag play: mitigated busy waiting by introducing delay
Sign up for free to subscribe to this conversation on GitHub. Already have an account? Sign in.

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants