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 );
51 void reset( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr,
float conv_frequency );
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_;
93 boost::shared_ptr<naoqi::recorder::GlobalRecorder>
gr_;
float buffer_duration_
Definition: joint_state.hpp:86
bool is_initialized_
Definition: joint_state.hpp:90
int counter_
Definition: joint_state.hpp:97
void bufferize(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
Definition: joint_state.cpp:88
bool isSubscribed() const
Definition: joint_state.hpp:75
float buffer_frequency_
Definition: joint_state.hpp:95
void setBufferDuration(float duration)
Definition: joint_state.cpp:104
std::string topic_
Definition: joint_state.hpp:81
Definition: joint_state.hpp:42
float conv_frequency_
Definition: joint_state.hpp:96
boost::circular_buffer< sensor_msgs::JointState > bufferJoinState_
Definition: joint_state.hpp:83
std::string topic() const
Definition: joint_state.hpp:60
boost::mutex mutex_
Definition: joint_state.hpp:88
int max_counter_
Definition: joint_state.hpp:98
JointStateRecorder(const std::string &topic, float buffer_frequency=0)
Definition: joint_state.cpp:28
bool is_subscribed_
Definition: joint_state.hpp:91
void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float conv_frequency)
Definition: joint_state.cpp:69
boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr_
Definition: joint_state.hpp:93
bool isInitialized() const
Definition: joint_state.hpp:65
size_t buffer_size_
Definition: joint_state.hpp:85
void write(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
Definition: joint_state.cpp:37
void writeDump(const ros::Time &time)
Definition: joint_state.cpp:49
void subscribe(bool state)
Definition: joint_state.hpp:70
boost::circular_buffer< std::vector< geometry_msgs::TransformStamped > > bufferTF_
Definition: joint_state.hpp:84