naoqidriver
Data Structures | Public Member Functions | Private Attributes | Friends
naoqi::recorder::Recorder Class Reference

Recorder concept interface. More...

#include <recorder.hpp>

Data Structures

struct  RecorderConcept
 
struct  RecorderModel
 

Public Member Functions

template<typename T >
 Recorder (T rec)
 Constructor for recorder interface. More...
 
bool isInitialized () const
 checks if the recorder is correctly initialized on the ros-master @ More...
 
void subscribe (bool state)
 
bool isSubscribed () const
 checks if the recorder has a subscription and is hence allowed to record More...
 
std::string topic () const
 
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 More...
 
void writeDump (const ros::Time &time)
 
void setBufferDuration (float duration)
 

Private Attributes

boost::shared_ptr< RecorderConceptrecPtr_
 

Friends

bool operator== (const Recorder &lhs, const Recorder &rhs)
 

Detailed Description

Recorder 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 recorder instance has to implement the virtual functions mentioned in the concept

Constructor & Destructor Documentation

template<typename T >
naoqi::recorder::Recorder::Recorder ( rec)
inline

Constructor for recorder interface.

Member Function Documentation

bool naoqi::recorder::Recorder::isInitialized ( ) const
inline

checks if the recorder is correctly initialized on the ros-master @

Returns
bool value indicating true for success
bool naoqi::recorder::Recorder::isSubscribed ( ) const
inline

checks if the recorder has a subscription and is hence allowed to record

Returns
bool value indicating true for number of sub > 0
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

Parameters
rosNodeHandle to advertise the recorder on
void naoqi::recorder::Recorder::setBufferDuration ( float  duration)
inline
void naoqi::recorder::Recorder::subscribe ( bool  state)
inline
std::string naoqi::recorder::Recorder::topic ( ) const
inline
void naoqi::recorder::Recorder::writeDump ( const ros::Time &  time)
inline

Friends And Related Function Documentation

bool operator== ( const Recorder lhs,
const Recorder rhs 
)
friend

Field Documentation

boost::shared_ptr<RecorderConcept> naoqi::recorder::Recorder::recPtr_
private

The documentation for this class was generated from the following file: