Subscriber concept interface.
More...
#include <subscriber.hpp>
|
template<typename T > |
| Subscriber (T sub) |
| Constructor for subscriber interface. More...
|
|
bool | isInitialized () const |
| checks if the subscriber is correctly initialized on the ros-master @ More...
|
|
void | reset (ros::NodeHandle &nh) |
| initializes/resets the subscriber into ROS with a given nodehandle, this will be called at first for initialization or again when master uri has changed More...
|
|
std::string | name () const |
| getting the descriptive name for this subscriber instance More...
|
|
std::string | topic () const |
| getting the topic to subscriber on More...
|
|
Subscriber 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 subscriber instance has to implement the virtual functions mentioned in the concept
template<typename T >
naoqi::subscriber::Subscriber::Subscriber |
( |
T |
sub | ) |
|
|
inline |
Constructor for subscriber interface.
bool naoqi::subscriber::Subscriber::isInitialized |
( |
| ) |
const |
|
inline |
checks if the subscriber is correctly initialized on the ros-master @
- Returns
- bool value indicating true for success
std::string naoqi::subscriber::Subscriber::name |
( |
| ) |
const |
|
inline |
getting the descriptive name for this subscriber instance
- Returns
- string with the name
void naoqi::subscriber::Subscriber::reset |
( |
ros::NodeHandle & |
nh | ) |
|
|
inline |
initializes/resets the subscriber 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 register the subscriber on |
std::string naoqi::subscriber::Subscriber::topic |
( |
| ) |
const |
|
inline |
getting the topic to subscriber on
- Returns
- string indicating the topic
The documentation for this class was generated from the following file:
- /home/vrabaud/ros/ws_nao_dashboard/src/naoqi_driver/include/naoqi_driver/subscriber/subscriber.hpp