Publisher concept interface. More...
#include <publisher.hpp>
Classes | |
struct | PublisherConcept |
struct | PublisherModel |
Public Member Functions | |
bool | isInitialized () const |
checks if the publisher is correctly initialized on the ros-master @ | |
bool | isSubscribed () const |
checks if the publisher has a subscription and is hence allowed to publish | |
template<typename T > | |
Publisher (const T &pub) | |
Constructor for publisher interface. | |
void | reset (ros::NodeHandle &nh) |
initializes/resets the publisher into ROS with a given nodehandle, this will be called at first for initialization or again when master uri has changed | |
std::string | topic () const |
getting the topic to publish on | |
Private Attributes | |
boost::shared_ptr < PublisherConcept > | pubPtr_ |
Friends | |
bool | operator== (const Publisher &lhs, const Publisher &rhs) |
bool | operator== (const boost::shared_ptr< Publisher > &lhs, const boost::shared_ptr< Publisher > &rhs) |
Publisher concept interface.
Definition at line 41 of file publisher.hpp.
naoqi::publisher::Publisher::Publisher | ( | const T & | pub | ) | [inline] |
Constructor for publisher interface.
Definition at line 50 of file publisher.hpp.
bool naoqi::publisher::Publisher::isInitialized | ( | ) | const [inline] |
checks if the publisher is correctly initialized on the ros-master @
Definition at line 58 of file publisher.hpp.
bool naoqi::publisher::Publisher::isSubscribed | ( | ) | const [inline] |
checks if the publisher has a subscription and is hence allowed to publish
Definition at line 67 of file publisher.hpp.
void naoqi::publisher::Publisher::reset | ( | ros::NodeHandle & | nh | ) | [inline] |
initializes/resets the publisher into ROS with a given nodehandle, this will be called at first for initialization or again when master uri has changed
ros | NodeHandle to advertise the publisher on |
Definition at line 77 of file publisher.hpp.
std::string naoqi::publisher::Publisher::topic | ( | ) | const [inline] |
getting the topic to publish on
Definition at line 88 of file publisher.hpp.
Definition at line 93 of file publisher.hpp.
bool operator== | ( | const boost::shared_ptr< Publisher > & | lhs, |
const boost::shared_ptr< Publisher > & | rhs | ||
) | [friend] |
Definition at line 101 of file publisher.hpp.
boost::shared_ptr<PublisherConcept> naoqi::publisher::Publisher::pubPtr_ [private] |
Definition at line 154 of file publisher.hpp.