Go to the documentation of this file.
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;
virtual bool isInitialized() const =0
bool isSubscribed() const
checks if the publisher has a subscription and is hence allowed to publish
virtual bool isSubscribed() const =0
void reset(ros::NodeHandle &nh)
std::string topic() const
friend bool operator==(const Publisher &lhs, const Publisher &rhs)
bool isSubscribed() const
std::string topic() const
getting the topic to publish on
boost::shared_ptr< PublisherConcept > pubPtr_
virtual std::string topic() const =0
bool isInitialized() const
virtual void reset(ros::NodeHandle &nh)=0
virtual ~PublisherConcept()
bool isInitialized() const
checks if the publisher is correctly initialized on the ros-master @
friend bool operator==(const boost::shared_ptr< Publisher > &lhs, const boost::shared_ptr< Publisher > &rhs)
Publisher concept interface.
void reset(ros::NodeHandle &nh)
initializes/resets the publisher into ROS with a given nodehandle, this will be called at first for i...
PublisherModel(const T &other)
Publisher(const T &pub)
Constructor for publisher interface.
naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06