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