GlobalRecorder concept interface. More...
#include <audio.hpp>
Public Member Functions | |
AudioEventRegister () | |
Constructor for recorder interface. More... | |
AudioEventRegister (const std::string &name, const float &frequency, const qi::SessionPtr &session) | |
void | isDumping (bool state) |
void | isPublishing (bool state) |
void | isRecording (bool state) |
void | processRemote (int nbOfChannels, int samplesByChannel, qi::AnyValue altimestamp, qi::AnyValue buffer) |
void | resetPublisher (ros::NodeHandle &nh) |
void | resetRecorder (boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr) |
void | setBufferDuration (float duration) |
void | startProcess () |
void | stopProcess () |
void | writeDump (const ros::Time &time) |
~AudioEventRegister () | |
Private Member Functions | |
void | onEvent () |
void | registerCallback () |
void | unregisterCallback () |
Private Attributes | |
std::vector< uint8_t > | channelMap |
boost::shared_ptr< converter::AudioEventConverter > | converter_ |
bool | isDumping_ |
bool | isPublishing_ |
bool | isRecording_ |
bool | isStarted_ |
qi::AnyObject | p_audio_ |
qi::FutureSync< qi::AnyObject > | p_audio_extractor_request |
qi::AnyObject | p_robot_model_ |
boost::mutex | processing_mutex_ |
boost::shared_ptr< publisher::BasicPublisher< naoqi_bridge_msgs::AudioBuffer > > | publisher_ |
boost::shared_ptr< recorder::BasicEventRecorder< naoqi_bridge_msgs::AudioBuffer > > | recorder_ |
unsigned int | serviceId |
qi::SessionPtr | session_ |
boost::mutex | subscription_mutex_ |
GlobalRecorder concept interface.
Definition at line 53 of file event/audio.hpp.
naoqi::AudioEventRegister::AudioEventRegister | ( | ) |
Constructor for recorder interface.
Definition at line 35 of file event/audio.cpp.
naoqi::AudioEventRegister::AudioEventRegister | ( | const std::string & | name, |
const float & | frequency, | ||
const qi::SessionPtr & | session | ||
) |
Definition at line 39 of file event/audio.cpp.
naoqi::AudioEventRegister::~AudioEventRegister | ( | ) |
Definition at line 72 of file event/audio.cpp.
void naoqi::AudioEventRegister::isDumping | ( | bool | state | ) |
Definition at line 149 of file event/audio.cpp.
void naoqi::AudioEventRegister::isPublishing | ( | bool | state | ) |
Definition at line 143 of file event/audio.cpp.
void naoqi::AudioEventRegister::isRecording | ( | bool | state | ) |
Definition at line 137 of file event/audio.cpp.
|
private |
void naoqi::AudioEventRegister::processRemote | ( | int | nbOfChannels, |
int | samplesByChannel, | ||
qi::AnyValue | altimestamp, | ||
qi::AnyValue | buffer | ||
) |
Definition at line 163 of file event/audio.cpp.
|
private |
Definition at line 155 of file event/audio.cpp.
void naoqi::AudioEventRegister::resetPublisher | ( | ros::NodeHandle & | nh | ) |
Definition at line 77 of file event/audio.cpp.
void naoqi::AudioEventRegister::resetRecorder | ( | boost::shared_ptr< naoqi::recorder::GlobalRecorder > | gr | ) |
Definition at line 82 of file event/audio.cpp.
void naoqi::AudioEventRegister::setBufferDuration | ( | float | duration | ) |
Definition at line 132 of file event/audio.cpp.
void naoqi::AudioEventRegister::startProcess | ( | ) |
Definition at line 87 of file event/audio.cpp.
void naoqi::AudioEventRegister::stopProcess | ( | ) |
Definition at line 109 of file event/audio.cpp.
|
private |
Definition at line 159 of file event/audio.cpp.
void naoqi::AudioEventRegister::writeDump | ( | const ros::Time & | time | ) |
Definition at line 124 of file event/audio.cpp.
|
private |
Definition at line 94 of file event/audio.hpp.
|
private |
Definition at line 86 of file event/audio.hpp.
|
private |
Definition at line 103 of file event/audio.hpp.
|
private |
Definition at line 101 of file event/audio.hpp.
|
private |
Definition at line 102 of file event/audio.hpp.
|
private |
Definition at line 100 of file event/audio.hpp.
|
private |
Definition at line 91 of file event/audio.hpp.
|
private |
Definition at line 93 of file event/audio.hpp.
|
private |
Definition at line 92 of file event/audio.hpp.
|
private |
Definition at line 98 of file event/audio.hpp.
|
private |
Definition at line 87 of file event/audio.hpp.
|
private |
Definition at line 88 of file event/audio.hpp.
|
private |
Definition at line 95 of file event/audio.hpp.
|
private |
Definition at line 90 of file event/audio.hpp.
|
private |
Definition at line 97 of file event/audio.hpp.