23 #include <boost/make_shared.hpp> 24 #include <boost/shared_ptr.hpp> 25 # include <boost/thread/mutex.hpp> 30 #include <geometry_msgs/TransformStamped.h> 65 return recPtr_->isInitialized();
95 recPtr_->reset( gr, frequency );
105 recPtr_->setBufferDuration(duration);
127 virtual std::string
topic()
const = 0;
146 recorder_->reset( gr, frequency );
151 return recorder_->isInitialized();
156 recorder_->subscribe( state );
161 return recorder_->isSubscribed();
166 return recorder_->topic();
171 recorder_->writeDump(time);
176 recorder_->setBufferDuration(duration);
virtual void subscribe(bool state)=0
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 in...
void setBufferDuration(float duration)
boost::shared_ptr< RecorderConcept > recPtr_
Recorder concept interface.
void setBufferDuration(float duration)
virtual std::string topic() const =0
void writeDump(const ros::Time &time)
virtual bool isSubscribed() const =0
virtual ~RecorderConcept()
std::string topic() const
virtual void setBufferDuration(float duration)=0
void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float frequency)
void subscribe(bool state)
bool isSubscribed() const
friend bool operator==(const Recorder &lhs, const Recorder &rhs)
bool isSubscribed() const
checks if the recorder has a subscription and is hence allowed to record
std::string topic() const
RecorderModel(const T &other)
virtual void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float frequency)=0
void writeDump(const ros::Time &time)
Recorder(T rec)
Constructor for recorder interface.
bool isInitialized() const
virtual void writeDump(const ros::Time &time)=0
virtual bool isInitialized() const =0
bool isInitialized() const
checks if the recorder is correctly initialized on the ros-master @
void subscribe(bool state)