Classes | Public Member Functions | Private Attributes | Friends | List of all members
naoqi::recorder::Recorder Class Reference

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

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

Definition at line 46 of file recorder.hpp.

Constructor & Destructor Documentation

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

Constructor for recorder interface.

Definition at line 55 of file recorder.hpp.

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

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

Returns
bool value indicating true for number of sub > 0

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

Parameters
rosNodeHandle 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.

Friends And Related Function Documentation

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

Definition at line 108 of file recorder.hpp.

Member Data Documentation

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

Definition at line 182 of file recorder.hpp.


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


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26