Go to the documentation of this file.
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_;
boost::circular_buffer< sensor_msgs::JointState > bufferJoinState_
void writeDump(const ros::Time &time)
boost::circular_buffer< std::vector< geometry_msgs::TransformStamped > > bufferTF_
std::string topic() const
bool isSubscribed() const
void write(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
void subscribe(bool state)
void setBufferDuration(float duration)
void bufferize(const sensor_msgs::JointState &js_msg, const std::vector< geometry_msgs::TransformStamped > &tf_transforms)
void reset(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float conv_frequency)
bool isInitialized() const
boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr_
JointStateRecorder(const std::string &topic, float buffer_frequency=0)
naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 3 2024 03:50:06