Publisher concept interface.
More...
#include <publisher.hpp>
|
template<typename T > |
| Publisher (const T &pub) |
| Constructor for publisher interface. More...
|
|
bool | isInitialized () const |
| checks if the publisher is correctly initialized on the ros-master @ More...
|
|
bool | isSubscribed () const |
| checks if the publisher has a subscription and is hence allowed to publish More...
|
|
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 More...
|
|
std::string | topic () const |
| getting the topic to publish on More...
|
|
Publisher concept interface.
- Note
- this defines an private concept struct, which each instance has to implement
-
a type erasure pattern in implemented here to avoid strict inheritance, thus each possible publisher instance has to implement the virtual functions mentioned in the concept
template<typename T >
naoqi::publisher::Publisher::Publisher |
( |
const T & |
pub | ) |
|
|
inline |
Constructor for publisher interface.
bool naoqi::publisher::Publisher::isInitialized |
( |
| ) |
const |
|
inline |
checks if the publisher is correctly initialized on the ros-master @
- Returns
- bool value indicating true for success
bool naoqi::publisher::Publisher::isSubscribed |
( |
| ) |
const |
|
inline |
checks if the publisher has a subscription and is hence allowed to publish
- Returns
- bool value indicating true for number of sub > 0
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
- Parameters
-
ros | NodeHandle to advertise the publisher on |
std::string naoqi::publisher::Publisher::topic |
( |
| ) |
const |
|
inline |
getting the topic to publish on
- Returns
- string indicating the topic
bool operator== |
( |
const boost::shared_ptr< Publisher > & |
lhs, |
|
|
const boost::shared_ptr< Publisher > & |
rhs |
|
) |
| |
|
friend |
The documentation for this class was generated from the following file:
- /home/vrabaud/ros/ws_nao_dashboard/src/naoqi_driver/include/naoqi_driver/publisher/publisher.hpp