#include <ros_com_patterns.h>


Public Member Functions | |
| void | receive (TMSG msg) |
| Feed (ros::NodeHandle *n, const std::string &topic, int qsize) | |
| virtual bool | hasNext () const override |
| virtual void | getNext (T &value) override |
| virtual void | getLatest (T &value) override |
Private Attributes | |
| std::list< T > | data_ |
| ros::Subscriber | subscriber_ |
| CONVERTER | converter_ |
ROS specific implementation of the AFeed communication pattern.
|
inline |
|
inlineoverridevirtual |
getLatest reads the latest data element and discards all previous
Implements adore::mad::AFeed< T >.
|
inlineoverridevirtual |
getNext reads the next data element
Implements adore::mad::AFeed< T >.
|
inlineoverridevirtual |
hasNext indicates whether there is more data to read
Implements adore::mad::AFeed< T >.
|
inline |
|
private |
|
private |
|
private |