18 #ifndef SUBSCRIBER_HPP
19 #define SUBSCRIBER_HPP
23 #include <boost/make_shared.hpp>
24 #include <boost/shared_ptr.hpp>
60 return subPtr_->isInitialized();
68 void reset( ros::NodeHandle& nh )
70 std::cout <<
name() <<
" is resetting" << std::endl;
72 std::cout <<
name() <<
" reset" << std::endl;
110 virtual void reset( ros::NodeHandle& nh ) = 0;
111 virtual std::string
name()
const = 0;
112 virtual std::string
topic()
const = 0;
Subscriber(T sub)
Constructor for subscriber interface.
Definition: subscriber.hpp:50
virtual std::string name() const =0
bool isInitialized() const
checks if the subscriber is correctly initialized on the ros-master @
Definition: subscriber.hpp:58
T subscriber_
Definition: subscriber.hpp:146
std::string name() const
Definition: subscriber.hpp:126
std::string topic() const
Definition: subscriber.hpp:131
virtual ~SubscriberConcept()
Definition: subscriber.hpp:108
std::string name() const
getting the descriptive name for this subscriber instance
Definition: subscriber.hpp:79
Definition: subscriber.hpp:120
Subscriber concept interface.
Definition: subscriber.hpp:41
Definition: subscriber.hpp:106
void reset(ros::NodeHandle &nh)
Definition: subscriber.hpp:141
bool isInitialized() const
Definition: subscriber.hpp:136
std::string topic() const
getting the topic to subscriber on
Definition: subscriber.hpp:88
friend bool operator==(const Subscriber &lhs, const Subscriber &rhs)
Definition: subscriber.hpp:93
boost::shared_ptr< SubscriberConcept > subPtr_
Definition: subscriber.hpp:149
SubscriberModel(const T &other)
Definition: subscriber.hpp:122
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 ...
Definition: subscriber.hpp:68