Go to the documentation of this file.
   37 #ifndef NODELET_NODELET_MUX_H_ 
   38 #define NODELET_NODELET_MUX_H_ 
   51   template <
typename T, 
typename Filter>
 
   71           ROS_ERROR (
"[nodelet::NodeletMUX::init] Need a 'input_topics' parameter to be set before continuing!");
 
   78         switch (input_topics.
getType ())
 
   82             if (input_topics.
size () == 1)
 
   84               ROS_ERROR (
"[nodelet::NodeletMUX::init] Only one topic given. Does it make sense to passthrough?");
 
   88             if (input_topics.
size () > 8)
 
   90               ROS_ERROR (
"[nodelet::NodeletMUX::init] More than 8 topics passed!");
 
   94             ROS_INFO_STREAM (
"[nodelet::NodeletMUX::init] Subscribing to " << input_topics.
size () << 
" user given topics as inputs:");
 
   95             for (
int d = 0; 
d < input_topics.
size (); ++
d)
 
  100             for (
int d = 0; 
d < input_topics.
size (); ++
d)
 
  111             switch (input_topics.
size ())
 
  150                 ROS_ERROR (
"[nodelet::NodeletMUX::init] Invalid 'input_topics' parameter given!");
 
  158             ROS_ERROR (
"[nodelet::NodeletMUX::init] Invalid 'input_topics' parameter given!");
 
  163         ts_->registerCallback (boost::bind (&
NodeletMUX<T,Filter>::input, 
this, boost::placeholders::_1, boost::placeholders::_2, boost::placeholders::_3, boost::placeholders::_4, boost::placeholders::_5, boost::placeholders::_6, boost::placeholders::_7, boost::placeholders::_8));
 
  
boost::shared_ptr< T > TPtr
boost::shared_ptr< message_filters::TimeSynchronizer< T, T, T, T, T, T, T, T > > ts_
Synchronizer object.
boost::shared_ptr< const T > TConstPtr
std::vector< boost::shared_ptr< Filter > > filters_
A vector of message filters.
bool getParam(const std::string &key, bool &b) const
ros::NodeHandle & getMTPrivateNodeHandle() const
void filter_cb(const TConstPtr &input)
void publish(const boost::shared_ptr< M > &message) const
int maximum_queue_size_
The maximum number of messages that we can store in the queue.
message_filters::PassThrough< T > nf_
Null filter.
ros::Publisher pub_output_
The output ROS publisher.
virtual void onInit()
Nodelet initialization routine.
void add(const EventType &evt)
#define ROS_INFO_STREAM(args)
const Type & getType() const
void input(const TConstPtr &in1, const TConstPtr &in2, const TConstPtr &in3, const TConstPtr &in4, const TConstPtr &in5, const TConstPtr &in6, const TConstPtr &in7, const TConstPtr &in8)
NodeletMUX represent a mux nodelet for topics: it takes N (<=8) input topics, and publishes all of th...
ros::NodeHandle private_nh_
ROS local node handle.
nodelet_topic_tools
Author(s): Radu Bogdan Rusu, Tully Foote, Michael Carroll 
autogenerated on Mon May 12 2025 02:38:32