Public Member Functions | Private Attributes
swri::TypedSubscriberImpl< M, T > Class Template Reference

#include <subscriber_impl.h>

Inheritance diagram for swri::TypedSubscriberImpl< M, T >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

template<class M2 >
boost::enable_if
< ros::message_traits::HasHeader
< M2 >, void >::type 
handleMessage (const boost::shared_ptr< M const > &msg)
template<class M2 >
boost::disable_if
< ros::message_traits::HasHeader
< M2 >, void >::type 
handleMessage (const boost::shared_ptr< M const > &msg)
 TypedSubscriberImpl (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const ros::TransportHints &transport_hints)

Private Attributes

void(T::* callback_ )(const boost::shared_ptr< M const > &)
T * obj_

Detailed Description

template<class M, class T>
class swri::TypedSubscriberImpl< M, T >

Definition at line 295 of file subscriber_impl.h.


Constructor & Destructor Documentation

template<class M , class T >
swri::TypedSubscriberImpl< M, T >::TypedSubscriberImpl ( ros::NodeHandle nh,
const std::string &  topic,
uint32_t  queue_size,
void(T::*)(const boost::shared_ptr< M const > &)  fp,
T *  obj,
const ros::TransportHints transport_hints 
) [inline]

Definition at line 301 of file subscriber_impl.h.


Member Function Documentation

template<class M , class T >
template<class M2 >
boost::enable_if< ros::message_traits::HasHeader<M2>, void>::type swri::TypedSubscriberImpl< M, T >::handleMessage ( const boost::shared_ptr< M const > &  msg) [inline]

Definition at line 332 of file subscriber_impl.h.

template<class M , class T >
template<class M2 >
boost::disable_if< ros::message_traits::HasHeader<M2>, void>::type swri::TypedSubscriberImpl< M, T >::handleMessage ( const boost::shared_ptr< M const > &  msg) [inline]

Definition at line 341 of file subscriber_impl.h.


Member Data Documentation

template<class M , class T >
void(T::* swri::TypedSubscriberImpl< M, T >::callback_)(const boost::shared_ptr< M const > &) [private]

Definition at line 298 of file subscriber_impl.h.

template<class M , class T >
T* swri::TypedSubscriberImpl< M, T >::obj_ [private]

Definition at line 297 of file subscriber_impl.h.


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


swri_roscpp
Author(s):
autogenerated on Thu Jun 6 2019 20:34:48