18 #ifndef EVENT_REGISTER_HPP 19 #define EVENT_REGISTER_HPP 23 #include <boost/make_shared.hpp> 24 #include <boost/shared_ptr.hpp> 25 #include <boost/thread/mutex.hpp> 27 #include <qi/session.hpp> 44 template <
typename Converter,
typename Publisher,
typename Recorder>
54 EventRegister(
const std::string& key,
const qi::SessionPtr& session );
void writeDump(const ros::Time &time)
boost::shared_ptr< Publisher > publisher_
void isRecording(bool state)
void resetPublisher(ros::NodeHandle &nh)
void setBufferDuration(float duration)
boost::shared_ptr< Converter > converter_
void unregisterCallback()
EventRegister()
Constructor for recorder interface.
boost::shared_ptr< Recorder > recorder_
void isPublishing(bool state)
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
GlobalRecorder concept interface.
void isDumping(bool state)