Go to the documentation of this file.
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;
bool isInitialized() const
checks if the subscriber is correctly initialized on the ros-master @
boost::shared_ptr< SubscriberConcept > subPtr_
bool isInitialized() const
virtual std::string topic() const =0
Subscriber concept interface.
std::string topic() const
void reset(ros::NodeHandle &nh)
virtual bool isInitialized() const =0
friend bool operator==(const Subscriber &lhs, const Subscriber &rhs)
virtual void reset(ros::NodeHandle &nh)=0
virtual std::string name() const =0
virtual ~SubscriberConcept()
SubscriberModel(const T &other)
Subscriber(T sub)
Constructor for subscriber interface.
std::string topic() const
getting the topic to subscriber on
std::string name() const
getting the descriptive name for this subscriber instance
void reset(ros::NodeHandle &nh)
initializes/resets the subscriber into ROS with a given nodehandle, this will be called at first for ...
naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06