Public Member Functions | Private Member Functions | Private Attributes
nodelet_topic_tools::NodeletThrottle< M > Class Template Reference

#include <nodelet_throttle.h>

Inheritance diagram for nodelet_topic_tools::NodeletThrottle< M >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 NodeletThrottle ()
 ~NodeletThrottle ()

Private Member Functions

void callback (const boost::shared_ptr< const M > &cloud)
void connectCB ()
void disconnectCB ()
virtual void onInit ()
void reconfigure (nodelet_topic_tools::NodeletThrottleConfig &config, uint32_t level)

Private Attributes

boost::mutex connect_mutex_
ros::Time last_update_
double max_update_rate_
ros::NodeHandle nh_
ros::Publisher pub_
dynamic_reconfigure::Server
< nodelet_topic_tools::NodeletThrottleConfig > * 
srv_
ros::Subscriber sub_

Detailed Description

template<typename M>
class nodelet_topic_tools::NodeletThrottle< M >

Definition at line 46 of file nodelet_throttle.h.


Constructor & Destructor Documentation

template<typename M >
nodelet_topic_tools::NodeletThrottle< M >::NodeletThrottle ( ) [inline]

Definition at line 50 of file nodelet_throttle.h.

template<typename M >
nodelet_topic_tools::NodeletThrottle< M >::~NodeletThrottle ( ) [inline]

Definition at line 54 of file nodelet_throttle.h.


Member Function Documentation

template<typename M >
void nodelet_topic_tools::NodeletThrottle< M >::callback ( const boost::shared_ptr< const M > &  cloud) [inline, private]

Definition at line 87 of file nodelet_throttle.h.

template<typename M >
void nodelet_topic_tools::NodeletThrottle< M >::connectCB ( ) [inline, private]

Definition at line 108 of file nodelet_throttle.h.

template<typename M >
void nodelet_topic_tools::NodeletThrottle< M >::disconnectCB ( ) [inline, private]

Definition at line 116 of file nodelet_throttle.h.

template<typename M >
virtual void nodelet_topic_tools::NodeletThrottle< M >::onInit ( ) [inline, private, virtual]

Implements nodelet::Nodelet.

Definition at line 65 of file nodelet_throttle.h.

template<typename M >
void nodelet_topic_tools::NodeletThrottle< M >::reconfigure ( nodelet_topic_tools::NodeletThrottleConfig &  config,
uint32_t  level 
) [inline, private]

Definition at line 103 of file nodelet_throttle.h.


Member Data Documentation

template<typename M >
boost::mutex nodelet_topic_tools::NodeletThrottle< M >::connect_mutex_ [private]

Definition at line 62 of file nodelet_throttle.h.

template<typename M >
ros::Time nodelet_topic_tools::NodeletThrottle< M >::last_update_ [private]

Definition at line 60 of file nodelet_throttle.h.

template<typename M >
double nodelet_topic_tools::NodeletThrottle< M >::max_update_rate_ [private]

Definition at line 61 of file nodelet_throttle.h.

template<typename M >
ros::NodeHandle nodelet_topic_tools::NodeletThrottle< M >::nh_ [private]

Reimplemented from nodelet::Nodelet.

Definition at line 124 of file nodelet_throttle.h.

template<typename M >
ros::Publisher nodelet_topic_tools::NodeletThrottle< M >::pub_ [private]

Definition at line 125 of file nodelet_throttle.h.

template<typename M >
dynamic_reconfigure::Server<nodelet_topic_tools::NodeletThrottleConfig>* nodelet_topic_tools::NodeletThrottle< M >::srv_ [private]

Definition at line 63 of file nodelet_throttle.h.

template<typename M >
ros::Subscriber nodelet_topic_tools::NodeletThrottle< M >::sub_ [private]

Definition at line 126 of file nodelet_throttle.h.


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


nodelet_topic_tools
Author(s): Radu Bogdan Rusu, Tully Foote
autogenerated on Wed Aug 26 2015 14:56:48