Classes | Public Member Functions | Private Attributes | Friends | List of all members
naoqi::subscriber::Subscriber Class Reference

Subscriber concept interface. More...

#include <subscriber.hpp>

Classes

struct  SubscriberConcept
 
struct  SubscriberModel
 

Public Member Functions

bool isInitialized () const
 checks if the subscriber is correctly initialized on the ros-master @ More...
 
std::string name () const
 getting the descriptive name for this subscriber instance More...
 
void reset (ros::NodeHandle &nh)
 initializes/resets the subscriber into ROS with a given nodehandle, this will be called at first for initialization or again when master uri has changed More...
 
template<typename T >
 Subscriber (T sub)
 Constructor for subscriber interface. More...
 
std::string topic () const
 getting the topic to subscriber on More...
 

Private Attributes

boost::shared_ptr< SubscriberConceptsubPtr_
 

Friends

bool operator== (const Subscriber &lhs, const Subscriber &rhs)
 

Detailed Description

Subscriber concept interface.

Note
this defines an private concept struct, which each instance has to implement
a type erasure pattern in implemented here to avoid strict inheritance, thus each possible subscriber instance has to implement the virtual functions mentioned in the concept

Definition at line 41 of file subscriber.hpp.

Constructor & Destructor Documentation

template<typename T >
naoqi::subscriber::Subscriber::Subscriber ( sub)
inline

Constructor for subscriber interface.

Definition at line 50 of file subscriber.hpp.

Member Function Documentation

bool naoqi::subscriber::Subscriber::isInitialized ( ) const
inline

checks if the subscriber is correctly initialized on the ros-master @

Returns
bool value indicating true for success

Definition at line 58 of file subscriber.hpp.

std::string naoqi::subscriber::Subscriber::name ( ) const
inline

getting the descriptive name for this subscriber instance

Returns
string with the name

Definition at line 79 of file subscriber.hpp.

void naoqi::subscriber::Subscriber::reset ( ros::NodeHandle nh)
inline

initializes/resets the subscriber into ROS with a given nodehandle, this will be called at first for initialization or again when master uri has changed

Parameters
rosNodeHandle to register the subscriber on

Definition at line 68 of file subscriber.hpp.

std::string naoqi::subscriber::Subscriber::topic ( ) const
inline

getting the topic to subscriber on

Returns
string indicating the topic

Definition at line 88 of file subscriber.hpp.

Friends And Related Function Documentation

bool operator== ( const Subscriber lhs,
const Subscriber rhs 
)
friend

Definition at line 93 of file subscriber.hpp.

Member Data Documentation

boost::shared_ptr<SubscriberConcept> naoqi::subscriber::Subscriber::subPtr_
private

Definition at line 149 of file subscriber.hpp.


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


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26