event/audio.cpp
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 #include <iostream>
19 #include <vector>
20 
21 #include <boost/make_shared.hpp>
22 
23 #include <ros/ros.h>
24 
25 #include <qi/anyobject.hpp>
26 
29 
30 #include "audio.hpp"
31 
32 namespace naoqi
33 {
34 
36 {
37 }
38 
39 AudioEventRegister::AudioEventRegister( const std::string& name, const float& frequency, const qi::SessionPtr& session )
40  : serviceId(0),
41  p_audio_( session->service("ALAudioDevice")),
42  p_robot_model_(session->service("ALRobotModel")),
43  session_(session),
44  isStarted_(false),
45  isPublishing_(false),
46  isRecording_(false),
47  isDumping_(false)
48 {
49  int micConfig = p_robot_model_.call<int>("_getMicrophoneConfig");
50  if(micConfig){
51  channelMap.push_back(3);
52  channelMap.push_back(5);
53  channelMap.push_back(0);
54  channelMap.push_back(2);
55  }
56  else{
57  channelMap.push_back(0);
58  channelMap.push_back(2);
59  channelMap.push_back(1);
60  channelMap.push_back(4);
61  }
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 );
65 
67  converter_->registerCallback( message_actions::RECORD, boost::bind(&recorder::BasicEventRecorder<naoqi_bridge_msgs::AudioBuffer>::write, recorder_, _1) );
68  converter_->registerCallback( message_actions::LOG, boost::bind(&recorder::BasicEventRecorder<naoqi_bridge_msgs::AudioBuffer>::bufferize, recorder_, _1) );
69 
70 }
71 
73 {
74  stopProcess();
75 }
76 
78 {
79  publisher_->reset(nh);
80 }
81 
83 {
84  recorder_->reset(gr, converter_->frequency());
85 }
86 
88 {
89  boost::mutex::scoped_lock start_lock(subscription_mutex_);
90  if (!isStarted_)
91  {
92  if(!serviceId)
93  {
94  serviceId = session_->registerService("ROS-Driver-Audio", shared_from_this());
95  p_audio_.call<void>(
96  "setClientPreferences",
97  "ROS-Driver-Audio",
98  48000,
99  0,
100  0
101  );
102  p_audio_.call<void>("subscribe","ROS-Driver-Audio");
103  std::cout << "Audio Extractor: Start" << std::endl;
104  }
105  isStarted_ = true;
106  }
107 }
108 
110 {
111  boost::mutex::scoped_lock stop_lock(subscription_mutex_);
112  if (isStarted_)
113  {
114  if(serviceId){
115  p_audio_.call<void>("unsubscribe", "ROS-Driver-Audio");
116  session_->unregisterService(serviceId);
117  serviceId = 0;
118  }
119  std::cout << "Audio Extractor: Stop" << std::endl;
120  isStarted_ = false;
121  }
122 }
123 
125 {
126  if (isStarted_)
127  {
128  recorder_->writeDump(time);
129  }
130 }
131 
133 {
134  recorder_->setBufferDuration(duration);
135 }
136 
138 {
139  boost::mutex::scoped_lock rec_lock(processing_mutex_);
140  isRecording_ = state;
141 }
142 
144 {
145  boost::mutex::scoped_lock pub_lock(processing_mutex_);
146  isPublishing_ = state;
147 }
148 
150 {
151  boost::mutex::scoped_lock dump_lock(processing_mutex_);
152  isDumping_ = state;
153 }
154 
156 {
157 }
158 
160 {
161 }
162 
163 void AudioEventRegister::processRemote(int nbOfChannels, int samplesByChannel, qi::AnyValue altimestamp, qi::AnyValue buffer)
164 {
165  naoqi_bridge_msgs::AudioBuffer msg = naoqi_bridge_msgs::AudioBuffer();
166  msg.header.stamp = ros::Time::now();
167  msg.frequency = 48000;
168  msg.channelMap = channelMap;
169 
170  std::pair<char*, size_t> buffer_pointer = buffer.asRaw();
171 
172  int16_t* remoteBuffer = (int16_t*)buffer_pointer.first;
173  int bufferSize = nbOfChannels * samplesByChannel;
174  msg.data = std::vector<int16_t>(remoteBuffer, remoteBuffer+bufferSize);
175 
176  std::vector<message_actions::MessageAction> actions;
177  boost::mutex::scoped_lock callback_lock(processing_mutex_);
178  if (isStarted_) {
179  // CHECK FOR PUBLISH
180  if ( isPublishing_ && publisher_->isSubscribed() )
181  {
182  actions.push_back(message_actions::PUBLISH);
183  }
184  // CHECK FOR RECORD
185  if ( isRecording_ )
186  {
187  actions.push_back(message_actions::RECORD);
188  }
189  if ( !isDumping_ )
190  {
191  actions.push_back(message_actions::LOG);
192  }
193  if (actions.size() >0)
194  {
195  converter_->callAll( actions, msg );
196  }
197  }
198 
199 }
200 
201 }//namespace
msg
AudioEventRegister()
Constructor for recorder interface.
Definition: event/audio.cpp:35
std::vector< uint8_t > channelMap
Definition: event/audio.hpp:94
void writeDump(const ros::Time &time)
void isRecording(bool state)
qi::AnyObject p_robot_model_
Definition: event/audio.hpp:92
void resetPublisher(ros::NodeHandle &nh)
Definition: event/audio.cpp:77
void processRemote(int nbOfChannels, int samplesByChannel, qi::AnyValue altimestamp, qi::AnyValue buffer)
void resetRecorder(boost::shared_ptr< naoqi::recorder::GlobalRecorder > gr)
Definition: event/audio.cpp:82
boost::mutex subscription_mutex_
Definition: event/audio.hpp:97
boost::shared_ptr< publisher::BasicPublisher< naoqi_bridge_msgs::AudioBuffer > > publisher_
Definition: event/audio.hpp:87
void isDumping(bool state)
void isPublishing(bool state)
boost::shared_ptr< converter::AudioEventConverter > converter_
Definition: event/audio.hpp:86
static Time now()
boost::mutex processing_mutex_
Definition: event/audio.hpp:98
void setBufferDuration(float duration)
boost::shared_ptr< recorder::BasicEventRecorder< naoqi_bridge_msgs::AudioBuffer > > recorder_
Definition: event/audio.hpp:88


naoqi_driver
Author(s): Karsten Knese
autogenerated on Sat Feb 15 2020 03:24:26