Recorder concept interface. More...
#include <recorder.hpp>
Classes | |
struct | RecorderConcept |
struct | RecorderModel |
Public Member Functions | |
bool | isInitialized () const |
checks if the recorder is correctly initialized on the ros-master @ | |
bool | isSubscribed () const |
checks if the recorder has a subscription and is hence allowed to record | |
template<typename T > | |
Recorder (T rec) | |
Constructor for recorder interface. | |
void | reset (boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float frequency) |
initializes/resets the recorder into ROS with a given nodehandle, this will be called at first for initialization or again when master uri has changed | |
void | setBufferDuration (float duration) |
void | subscribe (bool state) |
std::string | topic () const |
void | writeDump (const ros::Time &time) |
Private Attributes | |
boost::shared_ptr < RecorderConcept > | recPtr_ |
Friends | |
bool | operator== (const Recorder &lhs, const Recorder &rhs) |
Recorder concept interface.
Definition at line 46 of file recorder.hpp.
naoqi::recorder::Recorder::Recorder | ( | T | rec | ) | [inline] |
Constructor for recorder interface.
Definition at line 55 of file recorder.hpp.
bool naoqi::recorder::Recorder::isInitialized | ( | ) | const [inline] |
checks if the recorder is correctly initialized on the ros-master @
Definition at line 63 of file recorder.hpp.
bool naoqi::recorder::Recorder::isSubscribed | ( | ) | const [inline] |
checks if the recorder has a subscription and is hence allowed to record
Definition at line 78 of file recorder.hpp.
void naoqi::recorder::Recorder::reset | ( | boost::shared_ptr< naoqi::recorder::GlobalRecorder > | gr, |
float | frequency | ||
) | [inline] |
initializes/resets the recorder 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 recorder on |
Definition at line 93 of file recorder.hpp.
void naoqi::recorder::Recorder::setBufferDuration | ( | float | duration | ) | [inline] |
Definition at line 103 of file recorder.hpp.
void naoqi::recorder::Recorder::subscribe | ( | bool | state | ) | [inline] |
Definition at line 69 of file recorder.hpp.
std::string naoqi::recorder::Recorder::topic | ( | ) | const [inline] |
Definition at line 83 of file recorder.hpp.
void naoqi::recorder::Recorder::writeDump | ( | const ros::Time & | time | ) | [inline] |
Definition at line 98 of file recorder.hpp.
Definition at line 108 of file recorder.hpp.
boost::shared_ptr<RecorderConcept> naoqi::recorder::Recorder::recPtr_ [private] |
Definition at line 182 of file recorder.hpp.