23 #include <boost/make_shared.hpp>
24 #include <boost/shared_ptr.hpp>
60 return pubPtr_->isInitialized();
77 void reset( ros::NodeHandle& nh )
79 std::cout <<
topic() <<
" is resetting" << std::endl;
81 std::cout <<
topic() <<
" reset" << std::endl;
101 friend bool operator==(
const boost::shared_ptr<Publisher>& lhs,
const boost::shared_ptr<Publisher>& rhs )
116 virtual void reset( ros::NodeHandle& nh ) = 0;
117 virtual std::string
topic()
const = 0;
bool isSubscribed() const
checks if the publisher has a subscription and is hence allowed to publish
Definition: publisher.hpp:67
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...
Definition: publisher.hpp:77
bool isInitialized() const
checks if the publisher is correctly initialized on the ros-master @
Definition: publisher.hpp:58
Definition: publisher.hpp:111
virtual void reset(ros::NodeHandle &nh)=0
boost::shared_ptr< PublisherConcept > pubPtr_
Definition: publisher.hpp:154
PublisherModel(const T &other)
Definition: publisher.hpp:127
virtual std::string topic() const =0
Publisher concept interface.
Definition: publisher.hpp:41
virtual ~PublisherConcept()
Definition: publisher.hpp:113
Definition: publisher.hpp:125
std::string topic() const
Definition: publisher.hpp:131
Publisher(const T &pub)
Constructor for publisher interface.
Definition: publisher.hpp:50
T publisher_
Definition: publisher.hpp:151
std::string topic() const
getting the topic to publish on
Definition: publisher.hpp:88
bool isSubscribed() const
Definition: publisher.hpp:141
bool isInitialized() const
Definition: publisher.hpp:136
friend bool operator==(const boost::shared_ptr< Publisher > &lhs, const boost::shared_ptr< Publisher > &rhs)
Definition: publisher.hpp:101
void reset(ros::NodeHandle &nh)
Definition: publisher.hpp:146
friend bool operator==(const Publisher &lhs, const Publisher &rhs)
Definition: publisher.hpp:93