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

NodeletDEMUX represent a demux nodelet for topics: it takes 1 input topic, and publishes on N (<=8) output topics. More...

#include <nodelet_demux.h>

Inheritance diagram for nodelet::NodeletDEMUX< T, message_filters::Subscriber< T > >:
Inheritance graph
[legend]

Public Member Functions

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
 

Private Member Functions

void input_callback (const TConstPtr &input)
 

Private Attributes

XmlRpc::XmlRpcValue output_topics_
 The list of output topics passed as a parameter. More...
 
ros::NodeHandle private_nh_
 ROS local node handle. More...
 
std::vector< boost::shared_ptr< ros::Publisher > > pubs_output_
 The output list of publishers. More...
 
ros::Subscriber sub_input_
 The input subscriber. 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>
class nodelet::NodeletDEMUX< T, message_filters::Subscriber< T > >

NodeletDEMUX represent a demux nodelet for topics: it takes 1 input topic, and publishes on N (<=8) output topics.

Author
Radu Bogdan Rusu

Definition at line 128 of file nodelet_demux.h.

Member Typedef Documentation

template<typename T >
typedef boost::shared_ptr<const T> nodelet::NodeletDEMUX< T, message_filters::Subscriber< T > >::TConstPtr
private

Definition at line 130 of file nodelet_demux.h.

Member Function Documentation

template<typename T >
void nodelet::NodeletDEMUX< T, message_filters::Subscriber< T > >::input_callback ( const TConstPtr input)
inlineprivate

Definition at line 184 of file nodelet_demux.h.

template<typename T >
void nodelet::NodeletDEMUX< T, message_filters::Subscriber< T > >::onInit ( )
inlinevirtual

Nodelet initialization routine.

Implements nodelet::Nodelet.

Definition at line 135 of file nodelet_demux.h.

Member Data Documentation

template<typename T >
XmlRpc::XmlRpcValue nodelet::NodeletDEMUX< T, message_filters::Subscriber< T > >::output_topics_
private

The list of output topics passed as a parameter.

Definition at line 199 of file nodelet_demux.h.

template<typename T >
ros::NodeHandle nodelet::NodeletDEMUX< T, message_filters::Subscriber< T > >::private_nh_
private

ROS local node handle.

Definition at line 191 of file nodelet_demux.h.

template<typename T >
std::vector<boost::shared_ptr <ros::Publisher> > nodelet::NodeletDEMUX< T, message_filters::Subscriber< T > >::pubs_output_
private

The output list of publishers.

Definition at line 193 of file nodelet_demux.h.

template<typename T >
ros::Subscriber nodelet::NodeletDEMUX< T, message_filters::Subscriber< T > >::sub_input_
private

The input subscriber.

Definition at line 195 of file nodelet_demux.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