Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
nodelet::NodeletMUX< T, Filter > Class Template Reference

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>

Inheritance diagram for nodelet::NodeletMUX< T, Filter >:
Inheritance graph
[legend]

Public Member Functions

 NodeletMUX ()
 
virtual void onInit ()
 Nodelet initialization routine. More...
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

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. More...
 
int maximum_queue_size_
 The maximum number of messages that we can store in the queue. More...
 
message_filters::PassThrough< T > nf_
 Null filter. More...
 
ros::NodeHandle private_nh_
 ROS local node handle. More...
 
ros::Publisher pub_output_
 The output ROS publisher. More...
 
boost::shared_ptr< message_filters::TimeSynchronizer< T, T, T, T, T, T, T, T > > ts_
 Synchronizer object. More...
 

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

template<typename T, typename Filter>
class nodelet::NodeletMUX< T, Filter >

NodeletMUX represent a mux nodelet for topics: it takes N (<=8) input topics, and publishes all of them on one output topic.

Author
Radu Bogdan Rusu

Definition at line 52 of file nodelet_mux.h.

Member Typedef Documentation

template<typename T , typename Filter >
typedef boost::shared_ptr<const T> nodelet::NodeletMUX< T, Filter >::TConstPtr
private

Definition at line 55 of file nodelet_mux.h.

template<typename T , typename Filter >
typedef boost::shared_ptr<T> nodelet::NodeletMUX< T, Filter >::TPtr
private

Definition at line 54 of file nodelet_mux.h.

Constructor & Destructor Documentation

template<typename T , typename Filter >
nodelet::NodeletMUX< T, Filter >::NodeletMUX ( )
inline

Definition at line 58 of file nodelet_mux.h.

Member Function Documentation

template<typename T , typename Filter >
void nodelet::NodeletMUX< T, Filter >::filter_cb ( const TConstPtr input)
inlineprivate

Definition at line 169 of file nodelet_mux.h.

template<typename T , typename Filter >
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 
)
inlineprivate

Definition at line 175 of file nodelet_mux.h.

template<typename T , typename Filter >
virtual void nodelet::NodeletMUX< T, Filter >::onInit ( )
inlinevirtual

Nodelet initialization routine.

Implements nodelet::Nodelet.

Definition at line 63 of file nodelet_mux.h.

Member Data Documentation

template<typename T , typename Filter >
std::vector<boost::shared_ptr<Filter> > nodelet::NodeletMUX< T, Filter >::filters_
private

A vector of message filters.

Definition at line 194 of file nodelet_mux.h.

template<typename T , typename Filter >
int nodelet::NodeletMUX< T, Filter >::maximum_queue_size_
private

The maximum number of messages that we can store in the queue.

Definition at line 191 of file nodelet_mux.h.

template<typename T , typename Filter >
message_filters::PassThrough<T> nodelet::NodeletMUX< T, Filter >::nf_
private

Null filter.

Definition at line 188 of file nodelet_mux.h.

template<typename T , typename Filter >
ros::NodeHandle nodelet::NodeletMUX< T, Filter >::private_nh_
private

ROS local node handle.

Definition at line 183 of file nodelet_mux.h.

template<typename T , typename Filter >
ros::Publisher nodelet::NodeletMUX< T, Filter >::pub_output_
private

The output ROS publisher.

Definition at line 185 of file nodelet_mux.h.

template<typename T , typename Filter >
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 197 of file nodelet_mux.h.


The documentation for this class was generated from the following file:


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