23 #include <boost/make_shared.hpp> 24 #include <boost/shared_ptr.hpp> 134 converter_->resetPublisher(nh);
139 converter_->resetRecorder(gr);
144 converter_->startProcess();
149 converter_->stopProcess();
154 converter_->writeDump(time);
159 converter_->setBufferDuration(duration);
164 converter_->isRecording(state);
169 converter_->isPublishing(state);
174 converter_->isDumping(state);
virtual void setBufferDuration(float duration)=0
virtual void stopProcess()=0
void writeDump(const ros::Time &time)
virtual void isDumping(bool state)=0
virtual void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)=0
virtual void writeDump(const ros::Time &time)=0
EventModel(const T &other)
void resetPublisher(ros::NodeHandle &nh)
void isRecording(bool state)
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
Event(T event)
Constructor for converter interface.
void setBufferDuration(float duration)
Converter concept interface.
boost::shared_ptr< EventConcept > eventPtr_
void writeDump(const ros::Time &time)
virtual void startProcess()=0
virtual void resetPublisher(ros::NodeHandle &nh)=0
virtual void isRecording(bool state)=0
virtual void isPublishing(bool state)=0
void setBufferDuration(float duration)
void isPublishing(bool state)
void isDumping(bool state)
void isPublishing(bool state)
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
void isRecording(bool state)
void resetPublisher(ros::NodeHandle &nh)
void isDumping(bool state)