23 #include <boost/make_shared.hpp>
24 #include <boost/shared_ptr.hpp>
62 void resetRecorder( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr )
111 virtual void resetRecorder(boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr) = 0;
114 virtual void writeDump(
const ros::Time& time) = 0;
virtual void setBufferDuration(float duration)=0
virtual void stopProcess()=0
void startProcess()
Definition: event.hpp:67
void writeDump(const ros::Time &time)
Definition: event.hpp:77
virtual void isDumping(bool state)=0
void startProcess()
Definition: event.hpp:142
virtual void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)=0
void stopProcess()
Definition: event.hpp:72
virtual void writeDump(const ros::Time &time)=0
EventModel(const T &other)
Definition: event.hpp:128
void resetPublisher(ros::NodeHandle &nh)
Definition: event.hpp:132
Definition: event.hpp:126
void isRecording(bool state)
Definition: event.hpp:162
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
Definition: event.hpp:137
Event(T event)
Constructor for converter interface.
Definition: event.hpp:53
void setBufferDuration(float duration)
Definition: event.hpp:82
Converter concept interface.
Definition: event.hpp:44
boost::shared_ptr< EventConcept > eventPtr_
Definition: event.hpp:180
void stopProcess()
Definition: event.hpp:147
void writeDump(const ros::Time &time)
Definition: event.hpp:152
virtual void startProcess()=0
Definition: event.hpp:107
virtual void resetPublisher(ros::NodeHandle &nh)=0
virtual void isRecording(bool state)=0
T converter_
Definition: event.hpp:177
virtual void isPublishing(bool state)=0
void setBufferDuration(float duration)
Definition: event.hpp:157
void isPublishing(bool state)
Definition: event.hpp:167
void isDumping(bool state)
Definition: event.hpp:97
virtual ~EventConcept()
Definition: event.hpp:109
void isPublishing(bool state)
Definition: event.hpp:92
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
Definition: event.hpp:62
void isRecording(bool state)
Definition: event.hpp:87
void resetPublisher(ros::NodeHandle &nh)
Definition: event.hpp:57
void isDumping(bool state)
Definition: event.hpp:172