naoqidriver
Data Structures | Public Member Functions | Private Attributes
naoqi::event::Event Class Reference

Converter concept interface. More...

#include <event.hpp>

Data Structures

struct  EventConcept
 
struct  EventModel
 

Public Member Functions

template<typename T >
 Event (T event)
 Constructor for converter interface. More...
 
void resetPublisher (ros::NodeHandle &nh)
 
void resetRecorder (boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
 
void startProcess ()
 
void stopProcess ()
 
void writeDump (const ros::Time &time)
 
void setBufferDuration (float duration)
 
void isRecording (bool state)
 
void isPublishing (bool state)
 
void isDumping (bool state)
 

Private Attributes

boost::shared_ptr< EventConcepteventPtr_
 

Detailed Description

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

Constructor & Destructor Documentation

template<typename T >
naoqi::event::Event::Event ( event)
inline

Constructor for converter interface.

Member Function Documentation

void naoqi::event::Event::isDumping ( bool  state)
inline
void naoqi::event::Event::isPublishing ( bool  state)
inline
void naoqi::event::Event::isRecording ( bool  state)
inline
void naoqi::event::Event::resetPublisher ( ros::NodeHandle &  nh)
inline
void naoqi::event::Event::resetRecorder ( boost::shared_ptr< naoqi::recorder::GlobalRecorder gr)
inline
void naoqi::event::Event::setBufferDuration ( float  duration)
inline
void naoqi::event::Event::startProcess ( )
inline
void naoqi::event::Event::stopProcess ( )
inline
void naoqi::event::Event::writeDump ( const ros::Time &  time)
inline

Field Documentation

boost::shared_ptr<EventConcept> naoqi::event::Event::eventPtr_
private

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