#include <joint_state.hpp>
Definition at line 42 of file recorder/joint_state.hpp.
◆ JointStateRecorder()
naoqi::recorder::JointStateRecorder::JointStateRecorder |
( |
const std::string & |
topic, |
|
|
float |
buffer_frequency = 0 |
|
) |
| |
◆ bufferize()
void naoqi::recorder::JointStateRecorder::bufferize |
( |
const sensor_msgs::JointState & |
js_msg, |
|
|
const std::vector< geometry_msgs::TransformStamped > & |
tf_transforms |
|
) |
| |
◆ isInitialized()
bool naoqi::recorder::JointStateRecorder::isInitialized |
( |
| ) |
const |
|
inline |
◆ isSubscribed()
bool naoqi::recorder::JointStateRecorder::isSubscribed |
( |
| ) |
const |
|
inline |
◆ reset()
◆ setBufferDuration()
void naoqi::recorder::JointStateRecorder::setBufferDuration |
( |
float |
duration | ) |
|
◆ subscribe()
void naoqi::recorder::JointStateRecorder::subscribe |
( |
bool |
state | ) |
|
|
inline |
◆ topic()
std::string naoqi::recorder::JointStateRecorder::topic |
( |
| ) |
const |
|
inline |
◆ write()
void naoqi::recorder::JointStateRecorder::write |
( |
const sensor_msgs::JointState & |
js_msg, |
|
|
const std::vector< geometry_msgs::TransformStamped > & |
tf_transforms |
|
) |
| |
◆ writeDump()
void naoqi::recorder::JointStateRecorder::writeDump |
( |
const ros::Time & |
time | ) |
|
◆ buffer_duration_
float naoqi::recorder::JointStateRecorder::buffer_duration_ |
|
protected |
◆ buffer_frequency_
float naoqi::recorder::JointStateRecorder::buffer_frequency_ |
|
protected |
◆ buffer_size_
size_t naoqi::recorder::JointStateRecorder::buffer_size_ |
|
protected |
◆ bufferJoinState_
boost::circular_buffer<sensor_msgs::JointState> naoqi::recorder::JointStateRecorder::bufferJoinState_ |
|
protected |
◆ bufferTF_
boost::circular_buffer< std::vector<geometry_msgs::TransformStamped> > naoqi::recorder::JointStateRecorder::bufferTF_ |
|
protected |
◆ conv_frequency_
float naoqi::recorder::JointStateRecorder::conv_frequency_ |
|
protected |
◆ counter_
int naoqi::recorder::JointStateRecorder::counter_ |
|
protected |
◆ gr_
◆ is_initialized_
bool naoqi::recorder::JointStateRecorder::is_initialized_ |
|
protected |
◆ is_subscribed_
bool naoqi::recorder::JointStateRecorder::is_subscribed_ |
|
protected |
◆ max_counter_
int naoqi::recorder::JointStateRecorder::max_counter_ |
|
protected |
◆ mutex_
boost::mutex naoqi::recorder::JointStateRecorder::mutex_ |
|
protected |
◆ topic_
std::string naoqi::recorder::JointStateRecorder::topic_ |
|
protected |
The documentation for this class was generated from the following files: