21 #include <boost/make_shared.hpp> 25 #include <qi/anyobject.hpp> 41 p_audio_( session->service(
"ALAudioDevice")),
62 publisher_ = boost::make_shared<publisher::BasicPublisher<naoqi_bridge_msgs::AudioBuffer> >( name );
63 recorder_ = boost::make_shared<recorder::BasicEventRecorder<naoqi_bridge_msgs::AudioBuffer> >( name );
64 converter_ = boost::make_shared<converter::AudioEventConverter>( name, frequency, session );
96 "setClientPreferences",
102 p_audio_.call<
void>(
"subscribe",
"ROS-Driver-Audio");
103 std::cout <<
"Audio Extractor: Start" << std::endl;
115 p_audio_.call<
void>(
"unsubscribe",
"ROS-Driver-Audio");
119 std::cout <<
"Audio Extractor: Stop" << std::endl;
165 naoqi_bridge_msgs::AudioBuffer
msg = naoqi_bridge_msgs::AudioBuffer();
167 msg.frequency = 48000;
170 std::pair<char*, size_t> buffer_pointer = buffer.asRaw();
172 int16_t* remoteBuffer = (int16_t*)buffer_pointer.first;
173 int bufferSize = nbOfChannels * samplesByChannel;
174 msg.data = std::vector<int16_t>(remoteBuffer, remoteBuffer+bufferSize);
176 std::vector<message_actions::MessageAction> actions;
193 if (actions.size() >0)
AudioEventRegister()
Constructor for recorder interface.
std::vector< uint8_t > channelMap
void writeDump(const ros::Time &time)
void isRecording(bool state)
qi::AnyObject p_robot_model_
void resetPublisher(ros::NodeHandle &nh)
void processRemote(int nbOfChannels, int samplesByChannel, qi::AnyValue altimestamp, qi::AnyValue buffer)
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
boost::mutex subscription_mutex_
boost::shared_ptr< publisher::BasicPublisher< naoqi_bridge_msgs::AudioBuffer > > publisher_
void isDumping(bool state)
void isPublishing(bool state)
boost::shared_ptr< converter::AudioEventConverter > converter_
void unregisterCallback()
boost::mutex processing_mutex_
void setBufferDuration(float duration)
boost::shared_ptr< recorder::BasicEventRecorder< naoqi_bridge_msgs::AudioBuffer > > recorder_