nodelet_demux.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNERff OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: nodelet_mux.h 27892 2010-02-25 06:47:29Z rusu $
35  *
36  */
37 #ifndef NODELET_NODELET_DEMUX_H_
38 #define NODELET_NODELET_DEMUX_H_
39 
40 #include <ros/ros.h>
41 #include <nodelet/nodelet.h>
44 
45 namespace nodelet
46 {
50  template <typename T, typename Subscriber = message_filters::Subscriber<T> >
51  class NodeletDEMUX: public Nodelet
52  {
54  public:
56 
57  void
58  onInit ()
59  {
61  sub_input_.subscribe (private_nh_, "input", 1, bind (&NodeletDEMUX<T,Subscriber>::input_callback, this, _1));
62 
63  if (!private_nh_.getParam ("output_topics", output_topics_))
64  {
65  ROS_ERROR ("[nodelet::NodeletDEMUX::init] Need a 'output_topics' parameter to be set before continuing!");
66  return;
67  }
68  // Check the type
69  switch (output_topics_.getType ())
70  {
72  {
73  if (output_topics_.size () == 1)
74  {
75  ROS_ERROR ("[nodelet::NodeletDEMUX::init] Only one topic given. Does it make sense to passthrough?");
76  return;
77  }
78 
79  if (output_topics_.size () > 8)
80  {
81  ROS_ERROR ("[nodelet::NodeletDEMUX::init] More than 8 topics passed!");
82  return;
83  }
84 
85  ROS_INFO_STREAM ("[nodelet::NodeletDEMUX::init] Publishing to " << output_topics_.size () << " user given topics as outputs:");
86  for (int d = 0; d < output_topics_.size (); ++d)
87  ROS_INFO_STREAM (" - " << (std::string)(output_topics_[d]));
88 
89  pubs_output_.resize (output_topics_.size ());
90  for (int d = 0; d < output_topics_.size (); ++d)
91  pubs_output_[d] = boost::make_shared<ros::Publisher>(private_nh_.template advertise<T> ((std::string)(output_topics_[d]), 1));
92  break;
93  }
94  default:
95  {
96  ROS_ERROR ("[nodelet::NodeletDEMUX::init] Invalid 'output_topics' parameter given!");
97  return;
98  }
99  }
100  }
101 
102  private:
103 
105  void
106  input_callback (const TConstPtr &input)
107  {
108  for (size_t d = 0; d < pubs_output_.size (); ++d)
109  pubs_output_[d]->publish (input);
110  }
111 
115  std::vector<boost::shared_ptr <ros::Publisher> > pubs_output_;
117  Subscriber sub_input_;
118 
119 
122  };
123 
127  template <typename T>
128  class NodeletDEMUX<T, message_filters::Subscriber<T> >: public Nodelet
129  {
131  public:
133 
134  void
136  {
138 
140 
141  if (!private_nh_.getParam ("output_topics", output_topics_))
142  {
143  ROS_ERROR ("[nodelet::NodeletDEMUX::init] Need a 'output_topics' parameter to be set before continuing!");
144  return;
145  }
146  // Check the type
147  switch (output_topics_.getType ())
148  {
150  {
151  if (output_topics_.size () == 1)
152  {
153  ROS_ERROR ("[nodelet::NodeletDEMUX::init] Only one topic given. Does it make sense to passthrough?");
154  return;
155  }
156 
157  if (output_topics_.size () > 8)
158  {
159  ROS_ERROR ("[nodelet::NodeletDEMUX::init] More than 8 topics passed!");
160  return;
161  }
162 
163  ROS_INFO_STREAM ("[nodelet::NodeletDEMUX::init] Publishing to " << output_topics_.size () << " user given topics as outputs:");
164  for (int d = 0; d < output_topics_.size (); ++d)
165  ROS_INFO_STREAM (" - " << (std::string)(output_topics_[d]));
166 
167  pubs_output_.resize (output_topics_.size ());
168  for (int d = 0; d < output_topics_.size (); ++d)
169  pubs_output_[d] = boost::make_shared<ros::Publisher>(private_nh_.template advertise<T> ((std::string)(output_topics_[d]), 1));
170  break;
171  }
172  default:
173  {
174  ROS_ERROR ("[nodelet::NodeletDEMUX::init] Invalid 'output_topics' parameter given!");
175  return;
176  }
177  }
178  }
179 
180  private:
181 
183  void
184  input_callback (const TConstPtr &input)
185  {
186  for (size_t d = 0; d < pubs_output_.size (); ++d)
187  pubs_output_[d]->publish (input);
188  }
189 
193  std::vector<boost::shared_ptr <ros::Publisher> > pubs_output_;
196 
197 
200  };
201 
202 }
203 #endif
d
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
int size() const
std::vector< boost::shared_ptr< ros::Publisher > > pubs_output_
The output list of publishers.
void input_callback(const TConstPtr &input)
boost::shared_ptr< const T > TConstPtr
Definition: nodelet_demux.h:53
std::vector< boost::shared_ptr< ros::Publisher > > pubs_output_
The output list of publishers.
Type const & getType() const
ros::NodeHandle & getPrivateNodeHandle() const
Subscriber sub_input_
The input subscriber.
void onInit()
Nodelet initialization routine.
Definition: nodelet_demux.h:58
#define ROS_INFO_STREAM(args)
NodeletDEMUX represent a demux nodelet for topics: it takes 1 input topic, and publishes on N (<=8) o...
Definition: nodelet_demux.h:51
bool getParam(const std::string &key, std::string &s) const
ros::NodeHandle private_nh_
ROS local node handle.
ros::NodeHandle private_nh_
ROS local node handle.
XmlRpc::XmlRpcValue output_topics_
The list of output topics passed as a parameter.
#define ROS_ERROR(...)
XmlRpc::XmlRpcValue output_topics_
The list of output topics passed as a parameter.


nodelet_topic_tools
Author(s): Radu Bogdan Rusu, Tully Foote
autogenerated on Mon Feb 18 2019 03:26:48