Public Member Functions | Private Attributes | List of all members
swri::BindSubscriberImpl< M > Class Template Reference

#include <subscriber_impl.h>

Inheritance diagram for swri::BindSubscriberImpl< M >:
Inheritance graph
[legend]

Public Member Functions

 BindSubscriberImpl (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const ros::TransportHints &transport_hints)
 
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)
 
- Public Member Functions inherited from swri::SubscriberImpl
ros::Duration age (const ros::Time &now) const
 
bool blockTimeouts (bool block)
 
bool inTimeout ()
 
const std::string & mappedTopic () const
 
ros::Duration maxLatency () const
 
ros::Duration maxPeriod () const
 
double meanFrequencyHz () const
 
ros::Duration meanLatency () const
 
ros::Duration meanPeriod () const
 
int messageCount () const
 
ros::Duration minLatency () const
 
ros::Duration minPeriod () const
 
int numPublishers () const
 
void resetStatistics ()
 
void setTimeout (const ros::Duration &time_out)
 
 SubscriberImpl ()
 
ros::Duration timeout () const
 
int timeoutCount ()
 
bool timeoutEnabled () const
 
bool timeoutsBlocked () const
 
const std::string & unmappedTopic () const
 
virtual ~SubscriberImpl ()
 

Private Attributes

boost::function< void(const boost::shared_ptr< M const > &)> callback_
 

Additional Inherited Members

- Protected Member Functions inherited from swri::SubscriberImpl
void checkTimeout (const ros::Time &now)
 
void processHeader (const ros::Time &stamp)
 
- Protected Attributes inherited from swri::SubscriberImpl
bool blocking_timeout_
 
bool in_timeout_
 
ros::Time last_header_stamp_
 
ros::Time last_receive_time_
 
std::string mapped_topic_
 
ros::Duration max_latency_
 
ros::Duration max_period_
 
int message_count_
 
ros::Duration min_latency_
 
ros::Duration min_period_
 
ros::Subscriber sub_
 
ros::Duration timeout_
 
int timeout_count_
 
ros::Duration total_latency_
 
ros::Duration total_periods_
 
std::string unmapped_topic_
 

Detailed Description

template<class M>
class swri::BindSubscriberImpl< M >

Definition at line 355 of file subscriber_impl.h.

Constructor & Destructor Documentation

◆ BindSubscriberImpl()

template<class M >
swri::BindSubscriberImpl< M >::BindSubscriberImpl ( ros::NodeHandle nh,
const std::string &  topic,
uint32_t  queue_size,
const boost::function< void(const boost::shared_ptr< M const > &)> &  callback,
const ros::TransportHints transport_hints 
)
inline

Definition at line 361 of file subscriber_impl.h.

Member Function Documentation

◆ handleMessage() [1/2]

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

Definition at line 390 of file subscriber_impl.h.

◆ handleMessage() [2/2]

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

Definition at line 399 of file subscriber_impl.h.

Member Data Documentation

◆ callback_

template<class M >
boost::function<void(const boost::shared_ptr< M const> &)> swri::BindSubscriberImpl< M >::callback_
private

Definition at line 357 of file subscriber_impl.h.


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


swri_roscpp
Author(s): P. J. Reed
autogenerated on Thu Jun 6 2024 02:33:09