40 #include "calibration_msgs/Interval.h"
52 int main(
int argc,
char **argv)
54 ros::init(argc,argv,
"interval_intersection");
62 for (
int i=1; i<argc; i++) {
63 names.push_back(argv[i]);
73 vector<ros::Subscriber> subscribers;
74 for (
size_t i=0; i < names.size(); i++) {
75 ROS_DEBUG(
"Listening On Topic [%s]", names[i].c_str());
76 subscribers.push_back(nh.
subscribe<calibration_msgs::Interval>(names[i], 200, intersector.getNewInputStream()));