interval_intersection_node.cpp
Go to the documentation of this file.
1 /**********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2009, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #include <vector>
37 
38 #include "ros/ros.h"
39 #include "ros/console.h"
40 #include "calibration_msgs/Interval.h"
42 
43 using namespace std;
44 using namespace interval_intersection;
45 
46 void myPublish(ros::Publisher* pub, calibration_msgs::Interval interval)
47 {
48  pub->publish(interval);
49 }
50 
51 // Main
52 int main(int argc, char **argv)
53 {
54  ros::init(argc,argv,"interval_intersection");
55 
56  if (argc < 2) {
57  ROS_INFO_STREAM_NAMED("interval_intersection","At least one interval topic must be given.\n");
58  return 0;
59  }
60 
61  vector<string> names;
62  for (int i=1; i<argc; i++) {
63  names.push_back(argv[i]);
64  }
65 
66  ros::NodeHandle nh;
67 
68  // Publisher
69  ros::Publisher publisher = nh.advertise<calibration_msgs::Interval>("interval",1);
70  // Intersector
71  IntervalIntersector intersector(boost::bind(&myPublish, &publisher, _1));
72  // Subscribe
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()));
77  }
78 
79  ROS_INFO_STREAM_NAMED("interval_intersection","Advertised interval");
80 
81  ros::spin();
82 
83  return 0;
84 }
85 
86 
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_INFO_STREAM_NAMED(name, args)
void myPublish(ros::Publisher *pub, calibration_msgs::Interval interval)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ROSCPP_DECL void spin()
int main(int argc, char **argv)
#define ROS_DEBUG(...)


interval_intersection
Author(s): Romain Thibaux
autogenerated on Thu Jun 6 2019 19:17:22