Public Member Functions | Protected Attributes | List of all members
naoqi::recorder::CameraRecorder Class Reference

#include <camera.hpp>

Public Member Functions

void bufferize (const sensor_msgs::ImagePtr &img, const sensor_msgs::CameraInfo &camera_info)
 
 CameraRecorder (const std::string &topic, float buffer_frequency)
 
bool isInitialized () const
 
bool isSubscribed () const
 
void reset (boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr, float conv_frequency)
 
void setBufferDuration (float duration)
 
void subscribe (bool state)
 
std::string topic () const
 
void write (const sensor_msgs::ImagePtr &img, const sensor_msgs::CameraInfo &camera_info)
 
void writeDump (const ros::Time &time)
 

Protected Attributes

boost::circular_buffer< std::pair< sensor_msgs::ImagePtr, sensor_msgs::CameraInfo > > buffer_
 
float buffer_duration_
 
float buffer_frequency_
 
size_t buffer_size_
 
float conv_frequency_
 
int counter_
 
boost::shared_ptr< naoqi::recorder::GlobalRecordergr_
 
bool is_initialized_
 
bool is_subscribed_
 
int max_counter_
 
boost::mutex mutex_
 
std::string topic_img_
 
std::string topic_info_
 

Detailed Description

Definition at line 43 of file recorder/camera.hpp.

Constructor & Destructor Documentation

naoqi::recorder::CameraRecorder::CameraRecorder ( const std::string &  topic,
float  buffer_frequency 
)

Definition at line 28 of file recorder/camera.cpp.

Member Function Documentation

void naoqi::recorder::CameraRecorder::bufferize ( const sensor_msgs::ImagePtr &  img,
const sensor_msgs::CameraInfo &  camera_info 
)

Definition at line 76 of file recorder/camera.cpp.

bool naoqi::recorder::CameraRecorder::isInitialized ( ) const
inline

Definition at line 64 of file recorder/camera.hpp.

bool naoqi::recorder::CameraRecorder::isSubscribed ( ) const
inline

Definition at line 74 of file recorder/camera.hpp.

void naoqi::recorder::CameraRecorder::reset ( boost::shared_ptr< naoqi::recorder::GlobalRecorder gr,
float  conv_frequency 
)

Definition at line 66 of file recorder/camera.cpp.

void naoqi::recorder::CameraRecorder::setBufferDuration ( float  duration)

Definition at line 90 of file recorder/camera.cpp.

void naoqi::recorder::CameraRecorder::subscribe ( bool  state)
inline

Definition at line 69 of file recorder/camera.hpp.

std::string naoqi::recorder::CameraRecorder::topic ( ) const
inline

Definition at line 59 of file recorder/camera.hpp.

void naoqi::recorder::CameraRecorder::write ( const sensor_msgs::ImagePtr &  img,
const sensor_msgs::CameraInfo &  camera_info 
)

Definition at line 37 of file recorder/camera.cpp.

void naoqi::recorder::CameraRecorder::writeDump ( const ros::Time time)

Definition at line 53 of file recorder/camera.cpp.

Member Data Documentation

boost::circular_buffer< std::pair<sensor_msgs::ImagePtr, sensor_msgs::CameraInfo> > naoqi::recorder::CameraRecorder::buffer_
protected

Definition at line 83 of file recorder/camera.hpp.

float naoqi::recorder::CameraRecorder::buffer_duration_
protected

Definition at line 85 of file recorder/camera.hpp.

float naoqi::recorder::CameraRecorder::buffer_frequency_
protected

Definition at line 93 of file recorder/camera.hpp.

size_t naoqi::recorder::CameraRecorder::buffer_size_
protected

Definition at line 84 of file recorder/camera.hpp.

float naoqi::recorder::CameraRecorder::conv_frequency_
protected

Definition at line 94 of file recorder/camera.hpp.

int naoqi::recorder::CameraRecorder::counter_
protected

Definition at line 95 of file recorder/camera.hpp.

boost::shared_ptr<naoqi::recorder::GlobalRecorder> naoqi::recorder::CameraRecorder::gr_
protected

Definition at line 89 of file recorder/camera.hpp.

bool naoqi::recorder::CameraRecorder::is_initialized_
protected

Definition at line 80 of file recorder/camera.hpp.

bool naoqi::recorder::CameraRecorder::is_subscribed_
protected

Definition at line 81 of file recorder/camera.hpp.

int naoqi::recorder::CameraRecorder::max_counter_
protected

Definition at line 96 of file recorder/camera.hpp.

boost::mutex naoqi::recorder::CameraRecorder::mutex_
protected

Definition at line 87 of file recorder/camera.hpp.

std::string naoqi::recorder::CameraRecorder::topic_img_
protected

Definition at line 91 of file recorder/camera.hpp.

std::string naoqi::recorder::CameraRecorder::topic_info_
protected

Definition at line 90 of file recorder/camera.hpp.


The documentation for this class was generated from the following files:


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26