audio.hpp
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 #ifndef AUDIO_EVENT_REGISTER_HPP
00019 #define AUDIO_EVENT_REGISTER_HPP
00020 
00021 #include <string>
00022 
00023 #include <boost/make_shared.hpp>
00024 #include <boost/shared_ptr.hpp>
00025 #include <boost/thread/mutex.hpp>
00026 #include <boost/enable_shared_from_this.hpp>
00027 
00028 #include <qi/session.hpp>
00029 
00030 #include <ros/ros.h>
00031 #include <naoqi_bridge_msgs/AudioBuffer.h>
00032 
00033 #include <naoqi_driver/tools.hpp>
00034 #include <naoqi_driver/recorder/globalrecorder.hpp>
00035 
00036 // Converter
00037 #include "../src/converters/audio.hpp"
00038 // Publisher
00039 #include "../src/publishers/basic.hpp"
00040 // Recorder
00041 #include "../recorder/basic_event.hpp"
00042 
00043 namespace naoqi
00044 {
00045 
00053 class AudioEventRegister: public boost::enable_shared_from_this<AudioEventRegister>
00054 {
00055 
00056 public:
00057 
00061   AudioEventRegister();
00062   AudioEventRegister( const std::string& name, const float& frequency, const qi::SessionPtr& session );
00063   ~AudioEventRegister();
00064 
00065   void resetPublisher( ros::NodeHandle& nh );
00066   void resetRecorder( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr );
00067 
00068   void startProcess();
00069   void stopProcess();
00070 
00071   void writeDump(const ros::Time& time);
00072   void setBufferDuration(float duration);
00073 
00074   void isRecording(bool state);
00075   void isPublishing(bool state);
00076   void isDumping(bool state);
00077 
00078   void processRemote(int nbOfChannels, int samplesByChannel, qi::AnyValue altimestamp, qi::AnyValue buffer);
00079 
00080 private:
00081   void registerCallback();
00082   void unregisterCallback();
00083   void onEvent();
00084 
00085 private:
00086   boost::shared_ptr<converter::AudioEventConverter> converter_;
00087   boost::shared_ptr<publisher::BasicPublisher<naoqi_bridge_msgs::AudioBuffer> > publisher_;
00088   boost::shared_ptr<recorder::BasicEventRecorder<naoqi_bridge_msgs::AudioBuffer> > recorder_;
00089 
00090   qi::SessionPtr session_;
00091   qi::AnyObject p_audio_;
00092   qi::AnyObject p_robot_model_;
00093   qi::FutureSync<qi::AnyObject> p_audio_extractor_request;
00094   std::vector<uint8_t> channelMap;
00095   unsigned int serviceId;
00096 
00097   boost::mutex subscription_mutex_;
00098   boost::mutex processing_mutex_;
00099 
00100   bool isStarted_;
00101   bool isPublishing_;
00102   bool isRecording_;
00103   bool isDumping_;
00104 
00105 }; // class
00106 
00107 QI_REGISTER_OBJECT(AudioEventRegister, processRemote)
00108 
00109 } //naoqi
00110 
00111 #endif


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