Go to the documentation of this file.
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;
void setBufferDuration(float duration)
bool isSubscribed() const
checks if the recorder has a subscription and is hence allowed to record
RecorderModel(const T &other)
void setBufferDuration(float duration)
boost::shared_ptr< RecorderConcept > recPtr_
bool isSubscribed() const
std::string topic() const
virtual void setBufferDuration(float duration)=0
virtual std::string topic() const =0
Recorder(T rec)
Constructor for recorder interface.
friend bool operator==(const Recorder &lhs, const Recorder &rhs)
virtual bool isInitialized() const =0
void subscribe(bool state)
void writeDump(const ros::Time &time)
virtual void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float frequency)=0
void writeDump(const ros::Time &time)
void subscribe(bool state)
Recorder concept interface.
bool isInitialized() const
checks if the recorder is correctly initialized on the ros-master @
bool isInitialized() const
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...
virtual void writeDump(const ros::Time &time)=0
std::string topic() const
virtual ~RecorderConcept()
virtual bool isSubscribed() const =0
virtual void subscribe(bool state)=0
void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float frequency)
naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06