18 #ifndef JOINT_STATE_RECORDER_HPP    19 #define JOINT_STATE_RECORDER_HPP    24 #include <boost/circular_buffer.hpp>    30 #include "../helpers/recorder_helpers.hpp"    35 #include <sensor_msgs/JointState.h>    48   void write( 
const sensor_msgs::JointState& js_msg,
    49               const std::vector<geometry_msgs::TransformStamped>& tf_transforms );
    53   void bufferize( 
const sensor_msgs::JointState& js_msg,
    54                   const std::vector<geometry_msgs::TransformStamped>& tf_transforms );
    60   inline std::string 
topic()
 const    84   boost::circular_buffer< std::vector<geometry_msgs::TransformStamped> > 
bufferTF_;
 
void bufferize(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
bool isSubscribed() const 
void setBufferDuration(float duration)
boost::circular_buffer< sensor_msgs::JointState > bufferJoinState_
std::string topic() const 
JointStateRecorder(const std::string &topic, float buffer_frequency=0)
void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float conv_frequency)
boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr_
bool isInitialized() const 
void write(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
void writeDump(const ros::Time &time)
void subscribe(bool state)
boost::circular_buffer< std::vector< geometry_msgs::TransformStamped > > bufferTF_