naoqidriver
audio.hpp
Go to the documentation of this file.
1 /*
2  * Copyright 2015 Aldebaran
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef AUDIO_EVENT_REGISTER_HPP
19 #define AUDIO_EVENT_REGISTER_HPP
20 
21 #include <string>
22 
23 #include <boost/make_shared.hpp>
24 #include <boost/shared_ptr.hpp>
25 #include <boost/thread/mutex.hpp>
26 #include <boost/enable_shared_from_this.hpp>
27 
28 #include <qi/session.hpp>
29 
30 #include <ros/ros.h>
31 #include <naoqi_bridge_msgs/AudioBuffer.h>
32 
33 #include <naoqi_driver/tools.hpp>
35 
36 // Converter
37 #include "../src/converters/audio.hpp"
38 // Publisher
39 #include "../src/publishers/basic.hpp"
40 // Recorder
41 #include "../recorder/basic_event.hpp"
42 
43 namespace naoqi
44 {
45 
53 class AudioEventRegister: public boost::enable_shared_from_this<AudioEventRegister>
54 {
55 
56 public:
57 
62  AudioEventRegister( const std::string& name, const float& frequency, const qi::SessionPtr& session );
64 
65  void resetPublisher( ros::NodeHandle& nh );
66  void resetRecorder( boost::shared_ptr<naoqi::recorder::GlobalRecorder> gr );
67 
68  void startProcess();
69  void stopProcess();
70 
71  void writeDump(const ros::Time& time);
72  void setBufferDuration(float duration);
73 
74  void isRecording(bool state);
75  void isPublishing(bool state);
76  void isDumping(bool state);
77 
78  void processRemote(int nbOfChannels, int samplesByChannel, qi::AnyValue altimestamp, qi::AnyValue buffer);
79 
80 private:
81  void registerCallback();
82  void unregisterCallback();
83  void onEvent();
84 
85 private:
86  boost::shared_ptr<converter::AudioEventConverter> converter_;
87  boost::shared_ptr<publisher::BasicPublisher<naoqi_bridge_msgs::AudioBuffer> > publisher_;
88  boost::shared_ptr<recorder::BasicEventRecorder<naoqi_bridge_msgs::AudioBuffer> > recorder_;
89 
90  qi::SessionPtr session_;
91  qi::AnyObject p_audio_;
92  qi::AnyObject p_robot_model_;
93  qi::FutureSync<qi::AnyObject> p_audio_extractor_request;
94  std::vector<uint8_t> channelMap;
95  unsigned int serviceId;
96 
97  boost::mutex mutex_;
98 
99  bool isStarted_;
103 
104 }; // class
105 
107 
108 } //naoqi
109 
110 #endif
unsigned int serviceId
Definition: audio.hpp:95
AudioEventRegister()
Constructor for recorder interface.
Definition: audio.cpp:35
bool isStarted_
Definition: audio.hpp:99
std::vector< uint8_t > channelMap
Definition: audio.hpp:94
void writeDump(const ros::Time &time)
Definition: audio.cpp:124
qi::FutureSync< qi::AnyObject > p_audio_extractor_request
Definition: audio.hpp:93
void stopProcess()
Definition: audio.cpp:109
void startProcess()
Definition: audio.cpp:87
void isRecording(bool state)
Definition: audio.cpp:137
QI_REGISTER_OBJECT(Driver, _whoIsYourDaddy, minidump, minidumpConverters, setBufferDuration, getBufferDuration, startPublishing, stopPublishing, getMasterURI, setMasterURI, setMasterURINet, getAvailableConverters, getSubscribedPublishers, addMemoryConverters, registerMemoryConverter, registerEventConverter, getFilesList, removeAllFiles, removeFiles, startRecording, startRecordingConverters, stopRecording, startLogging, stopLogging)
qi::AnyObject p_robot_model_
Definition: audio.hpp:92
void resetPublisher(ros::NodeHandle &nh)
Definition: audio.cpp:77
bool isPublishing_
Definition: audio.hpp:100
Definition: audio.cpp:29
void processRemote(int nbOfChannels, int samplesByChannel, qi::AnyValue altimestamp, qi::AnyValue buffer)
Definition: audio.cpp:163
qi::SessionPtr session_
Definition: audio.hpp:90
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
Definition: audio.cpp:82
qi::AnyObject p_audio_
Definition: audio.hpp:91
bool isRecording_
Definition: audio.hpp:101
~AudioEventRegister()
Definition: audio.cpp:72
boost::shared_ptr< publisher::BasicPublisher< naoqi_bridge_msgs::AudioBuffer > > publisher_
Definition: audio.hpp:87
void isDumping(bool state)
Definition: audio.cpp:149
void isPublishing(bool state)
Definition: audio.cpp:143
GlobalRecorder concept interface.
Definition: audio.hpp:53
bool isDumping_
Definition: audio.hpp:102
boost::shared_ptr< converter::AudioEventConverter > converter_
Definition: audio.hpp:86
boost::mutex mutex_
Definition: audio.hpp:97
void unregisterCallback()
Definition: audio.cpp:159
void setBufferDuration(float duration)
Definition: audio.cpp:132
boost::shared_ptr< recorder::BasicEventRecorder< naoqi_bridge_msgs::AudioBuffer > > recorder_
Definition: audio.hpp:88
void registerCallback()
Definition: audio.cpp:155