23 #include <boost/make_shared.hpp>
24 #include <boost/shared_ptr.hpp>
25 # include <boost/thread/mutex.hpp>
28 #include <rosbag/bag.h>
29 #include <rosbag/view.h>
30 #include <geometry_msgs/TransformStamped.h>
65 return recPtr_->isInitialized();
93 void reset( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr,
float frequency)
95 recPtr_->reset( gr, frequency );
105 recPtr_->setBufferDuration(duration);
127 virtual std::string
topic()
const = 0;
128 virtual void writeDump(
const ros::Time& time) = 0;
130 virtual void reset( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr,
float frequency ) = 0;
144 void reset( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr,
float frequency )
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...
Definition: recorder.hpp:93
void setBufferDuration(float duration)
Definition: recorder.hpp:174
Definition: recorder.hpp:138
boost::shared_ptr< RecorderConcept > recPtr_
Definition: recorder.hpp:182
Recorder concept interface.
Definition: recorder.hpp:46
void setBufferDuration(float duration)
Definition: recorder.hpp:103
virtual std::string topic() const =0
void writeDump(const ros::Time &time)
Definition: recorder.hpp:169
virtual bool isSubscribed() const =0
virtual ~RecorderConcept()
Definition: recorder.hpp:123
Definition: recorder.hpp:121
std::string topic() const
Definition: recorder.hpp:164
virtual void setBufferDuration(float duration)=0
void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float frequency)
Definition: recorder.hpp:144
void subscribe(bool state)
Definition: recorder.hpp:154
bool isSubscribed() const
Definition: recorder.hpp:159
friend bool operator==(const Recorder &lhs, const Recorder &rhs)
Definition: recorder.hpp:108
bool isSubscribed() const
checks if the recorder has a subscription and is hence allowed to record
Definition: recorder.hpp:78
std::string topic() const
Definition: recorder.hpp:83
RecorderModel(const T &other)
Definition: recorder.hpp:140
virtual void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float frequency)=0
void writeDump(const ros::Time &time)
Definition: recorder.hpp:98
Recorder(T rec)
Constructor for recorder interface.
Definition: recorder.hpp:55
bool isInitialized() const
Definition: recorder.hpp:149
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 @
Definition: recorder.hpp:63
T recorder_
Definition: recorder.hpp:179
void subscribe(bool state)
Definition: recorder.hpp:69