NodeletMUX represent a mux nodelet for topics: it takes N (<=8) input topics, and publishes all of them on one output topic. More...
#include <nodelet_mux.h>
Public Member Functions | |
NodeletMUX () | |
virtual void | onInit () |
Nodelet initialization routine. | |
Private Types | |
typedef boost::shared_ptr < const T > | TConstPtr |
typedef boost::shared_ptr< T > | TPtr |
Private Member Functions | |
void | filter_cb (const TConstPtr &input) |
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) |
Private Attributes | |
std::vector< boost::shared_ptr < Filter > > | filters_ |
A vector of message filters. | |
int | maximum_queue_size_ |
The maximum number of messages that we can store in the queue. | |
message_filters::PassThrough< T > | nf_ |
Null filter. | |
ros::NodeHandle | private_nh_ |
ROS local node handle. | |
ros::Publisher | pub_output_ |
The output ROS publisher. | |
boost::shared_ptr < message_filters::TimeSynchronizer < T, T, T, T, T, T, T, T > > | ts_ |
Synchronizer object. |
NodeletMUX represent a mux nodelet for topics: it takes N (<=8) input topics, and publishes all of them on one output topic.
Definition at line 52 of file nodelet_mux.h.
typedef boost::shared_ptr<const T> nodelet::NodeletMUX< T, Filter >::TConstPtr [private] |
Definition at line 55 of file nodelet_mux.h.
typedef boost::shared_ptr<T> nodelet::NodeletMUX< T, Filter >::TPtr [private] |
Definition at line 54 of file nodelet_mux.h.
nodelet::NodeletMUX< T, Filter >::NodeletMUX | ( | ) | [inline] |
Definition at line 59 of file nodelet_mux.h.
void nodelet::NodeletMUX< T, Filter >::filter_cb | ( | const TConstPtr & | input | ) | [inline, private] |
Definition at line 170 of file nodelet_mux.h.
void nodelet::NodeletMUX< T, Filter >::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 | ||
) | [inline, private] |
Definition at line 176 of file nodelet_mux.h.
virtual void nodelet::NodeletMUX< T, Filter >::onInit | ( | ) | [inline, virtual] |
Nodelet initialization routine.
Implements nodelet::Nodelet.
Definition at line 64 of file nodelet_mux.h.
std::vector<boost::shared_ptr<Filter> > nodelet::NodeletMUX< T, Filter >::filters_ [private] |
A vector of message filters.
Definition at line 195 of file nodelet_mux.h.
int nodelet::NodeletMUX< T, Filter >::maximum_queue_size_ [private] |
The maximum number of messages that we can store in the queue.
Definition at line 192 of file nodelet_mux.h.
message_filters::PassThrough<T> nodelet::NodeletMUX< T, Filter >::nf_ [private] |
Null filter.
Definition at line 189 of file nodelet_mux.h.
ros::NodeHandle nodelet::NodeletMUX< T, Filter >::private_nh_ [private] |
ROS local node handle.
Reimplemented from nodelet::Nodelet.
Definition at line 184 of file nodelet_mux.h.
ros::Publisher nodelet::NodeletMUX< T, Filter >::pub_output_ [private] |
The output ROS publisher.
Definition at line 186 of file nodelet_mux.h.
boost::shared_ptr<message_filters::TimeSynchronizer<T,T,T,T,T,T,T,T> > nodelet::NodeletMUX< T, Filter >::ts_ [private] |
Synchronizer object.
Definition at line 198 of file nodelet_mux.h.