audio.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2015 Aldebaran
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 #include <iostream>
00019 #include <vector>
00020 
00021 #include <boost/make_shared.hpp>
00022 
00023 #include <ros/ros.h>
00024 
00025 #include <qi/anyobject.hpp>
00026 
00027 #include <naoqi_driver/recorder/globalrecorder.hpp>
00028 #include <naoqi_driver/message_actions.h>
00029 
00030 #include "audio.hpp"
00031 
00032 namespace naoqi
00033 {
00034 
00035 AudioEventRegister::AudioEventRegister()
00036 {
00037 }
00038 
00039 AudioEventRegister::AudioEventRegister( const std::string& name, const float& frequency, const qi::SessionPtr& session )
00040   : serviceId(0),
00041     p_audio_( session->service("ALAudioDevice")),
00042     p_robot_model_(session->service("ALRobotModel")),
00043     session_(session),
00044     isStarted_(false),
00045     isPublishing_(false),
00046     isRecording_(false),
00047     isDumping_(false)
00048 {
00049   int micConfig = p_robot_model_.call<int>("_getMicrophoneConfig");
00050   if(micConfig){
00051     channelMap.push_back(3);
00052     channelMap.push_back(5);
00053     channelMap.push_back(0);
00054     channelMap.push_back(2);
00055   }
00056   else{
00057     channelMap.push_back(0);
00058     channelMap.push_back(2);
00059     channelMap.push_back(1);
00060     channelMap.push_back(4);
00061   }
00062   publisher_ = boost::make_shared<publisher::BasicPublisher<naoqi_bridge_msgs::AudioBuffer> >( name );
00063   recorder_ = boost::make_shared<recorder::BasicEventRecorder<naoqi_bridge_msgs::AudioBuffer> >( name );
00064   converter_ = boost::make_shared<converter::AudioEventConverter>( name, frequency, session );
00065 
00066   converter_->registerCallback( message_actions::PUBLISH, boost::bind(&publisher::BasicPublisher<naoqi_bridge_msgs::AudioBuffer>::publish, publisher_, _1) );
00067   converter_->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicEventRecorder<naoqi_bridge_msgs::AudioBuffer>::write, recorder_, _1) );
00068   converter_->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicEventRecorder<naoqi_bridge_msgs::AudioBuffer>::bufferize, recorder_, _1) );
00069 
00070 }
00071 
00072 AudioEventRegister::~AudioEventRegister()
00073 {
00074   stopProcess();
00075 }
00076 
00077 void AudioEventRegister::resetPublisher(ros::NodeHandle& nh)
00078 {
00079   publisher_->reset(nh);
00080 }
00081 
00082 void AudioEventRegister::resetRecorder( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr )
00083 {
00084   recorder_->reset(gr, converter_->frequency());
00085 }
00086 
00087 void AudioEventRegister::startProcess()
00088 {
00089   boost::mutex::scoped_lock start_lock(subscription_mutex_);
00090   if (!isStarted_)
00091   {
00092     if(!serviceId)
00093     {
00094       serviceId = session_->registerService("ROS-Driver-Audio", shared_from_this());
00095       p_audio_.call<void>(
00096               "setClientPreferences",
00097               "ROS-Driver-Audio",
00098               48000,
00099               0,
00100               0
00101               );
00102       p_audio_.call<void>("subscribe","ROS-Driver-Audio");
00103       std::cout << "Audio Extractor: Start" << std::endl;
00104     }
00105     isStarted_ = true;
00106   }
00107 }
00108 
00109 void AudioEventRegister::stopProcess()
00110 {
00111   boost::mutex::scoped_lock stop_lock(subscription_mutex_);
00112   if (isStarted_)
00113   {
00114     if(serviceId){
00115       p_audio_.call<void>("unsubscribe", "ROS-Driver-Audio");
00116       session_->unregisterService(serviceId);
00117       serviceId = 0;
00118     }
00119     std::cout << "Audio Extractor: Stop" << std::endl;
00120     isStarted_ = false;
00121   }
00122 }
00123 
00124 void AudioEventRegister::writeDump(const ros::Time& time)
00125 {
00126   if (isStarted_)
00127   {
00128     recorder_->writeDump(time);
00129   }
00130 }
00131 
00132 void AudioEventRegister::setBufferDuration(float duration)
00133 {
00134   recorder_->setBufferDuration(duration);
00135 }
00136 
00137 void AudioEventRegister::isRecording(bool state)
00138 {
00139   boost::mutex::scoped_lock rec_lock(processing_mutex_);
00140   isRecording_ = state;
00141 }
00142 
00143 void AudioEventRegister::isPublishing(bool state)
00144 {
00145   boost::mutex::scoped_lock pub_lock(processing_mutex_);
00146   isPublishing_ = state;
00147 }
00148 
00149 void AudioEventRegister::isDumping(bool state)
00150 {
00151   boost::mutex::scoped_lock dump_lock(processing_mutex_);
00152   isDumping_ = state;
00153 }
00154 
00155 void AudioEventRegister::registerCallback()
00156 {
00157 }
00158 
00159 void AudioEventRegister::unregisterCallback()
00160 {
00161 }
00162 
00163 void AudioEventRegister::processRemote(int nbOfChannels, int samplesByChannel, qi::AnyValue altimestamp, qi::AnyValue buffer)
00164 {
00165   naoqi_bridge_msgs::AudioBuffer msg = naoqi_bridge_msgs::AudioBuffer();
00166   msg.header.stamp = ros::Time::now();
00167   msg.frequency = 48000;
00168   msg.channelMap = channelMap;
00169 
00170   std::pair<char*, size_t> buffer_pointer = buffer.asRaw();
00171 
00172   int16_t* remoteBuffer = (int16_t*)buffer_pointer.first;
00173   int bufferSize = nbOfChannels * samplesByChannel;
00174   msg.data = std::vector<int16_t>(remoteBuffer, remoteBuffer+bufferSize);
00175 
00176   std::vector<message_actions::MessageAction> actions;
00177   boost::mutex::scoped_lock callback_lock(processing_mutex_);
00178   if (isStarted_) {
00179     // CHECK FOR PUBLISH
00180     if ( isPublishing_ && publisher_->isSubscribed() )
00181     {
00182       actions.push_back(message_actions::PUBLISH);
00183     }
00184     // CHECK FOR RECORD
00185     if ( isRecording_ )
00186     {
00187       actions.push_back(message_actions::RECORD);
00188     }
00189     if ( !isDumping_ )
00190     {
00191       actions.push_back(message_actions::LOG);
00192     }
00193     if (actions.size() >0)
00194     {
00195       converter_->callAll( actions, msg );
00196     }
00197   }
00198 
00199 }
00200 
00201 }//namespace


naoqi_driver
Author(s): Karsten Knese
autogenerated on Tue Jul 9 2019 03:21:56