23 #include <boost/make_shared.hpp> 24 #include <boost/shared_ptr.hpp> 60 return pubPtr_->isInitialized();
79 std::cout <<
topic() <<
" is resetting" << std::endl;
81 std::cout <<
topic() <<
" reset" << std::endl;
117 virtual std::string
topic()
const = 0;
133 return publisher_->topic();
138 return publisher_->isInitialized();
143 return publisher_->isSubscribed();
148 publisher_->reset( nh );
bool isSubscribed() const
checks if the publisher has a subscription and is hence allowed to publish
virtual bool isInitialized() const =0
virtual bool isSubscribed() const =0
void reset(ros::NodeHandle &nh)
initializes/resets the publisher into ROS with a given nodehandle, this will be called at first for i...
bool isInitialized() const
checks if the publisher is correctly initialized on the ros-master @
virtual void reset(ros::NodeHandle &nh)=0
boost::shared_ptr< PublisherConcept > pubPtr_
PublisherModel(const T &other)
virtual std::string topic() const =0
Publisher concept interface.
virtual ~PublisherConcept()
std::string topic() const
Publisher(const T &pub)
Constructor for publisher interface.
std::string topic() const
getting the topic to publish on
bool isSubscribed() const
bool isInitialized() const
friend bool operator==(const boost::shared_ptr< Publisher > &lhs, const boost::shared_ptr< Publisher > &rhs)
void reset(ros::NodeHandle &nh)
friend bool operator==(const Publisher &lhs, const Publisher &rhs)