18 #ifndef SUBSCRIBER_HPP    19 #define SUBSCRIBER_HPP    23 #include <boost/make_shared.hpp>    24 #include <boost/shared_ptr.hpp>    60     return subPtr_->isInitialized();
    70     std::cout << 
name() << 
" is resetting" << std::endl;
    72     std::cout << 
name() << 
" reset" << std::endl;
   111     virtual std::string 
name() 
const = 0;
   112     virtual std::string 
topic() 
const = 0;
   128       return subscriber_->name();
   133       return subscriber_->topic();
   138       return subscriber_->isInitialized();
   143       subscriber_->reset( nh );
 Subscriber(T sub)
Constructor for subscriber interface. 
virtual std::string name() const =0
bool isInitialized() const 
checks if the subscriber is correctly initialized on the ros-master @ 
std::string topic() const 
virtual ~SubscriberConcept()
std::string name() const 
getting the descriptive name for this subscriber instance 
Subscriber concept interface. 
void reset(ros::NodeHandle &nh)
bool isInitialized() const 
std::string topic() const 
getting the topic to subscriber on 
friend bool operator==(const Subscriber &lhs, const Subscriber &rhs)
boost::shared_ptr< SubscriberConcept > subPtr_
SubscriberModel(const T &other)
virtual void reset(ros::NodeHandle &nh)=0
virtual bool isInitialized() const =0
virtual std::string topic() const =0
void reset(ros::NodeHandle &nh)
initializes/resets the subscriber into ROS with a given nodehandle, this will be called at first for ...