Skip to main content
Version: QTrobot V2

Using QTrobot ReSpeaker microphone

Overview

 Level:  Advanced
 Goal:  learn how to use ReSpeaker microphone
 Requirements:

In this tutorial you will learn how to record audio data from QTrobot ReSpeaker Microphone.

Topics

The QTrobot ReSpeaker app (operating on QTRP) extracts data from the ReSpeaker Mic Array v2.0 and publishes it to the following topics. You can access these topics in a ROS environment, such as from QTPC.

Publisher:

/qt_respeaker_app/channel0 Channel 0: processed audio for ASR

/qt_respeaker_app/channel1 Channel 1: mic1 raw data

/qt_respeaker_app/channel2 Channel 2: mic2 raw data

/qt_respeaker_app/channel3 Channel 3: mic3 raw data

/qt_respeaker_app/channel4 Channel 4: mic4 raw data

/qt_respeaker_app/channel5 Channel 5: merged playback

/qt_respeaker_app/is_speaking VAD (Voice Activity Detection)

/qt_respeaker_app/sound_direction DOA (Direction of Arrival)

Record audio data on QTPC

Create a python project

First we create a python project for our tutorial. let's call it tutorial_qt_respeaker and add the required python file:

cd ~/catkin_ws/src
catkin_create_pkg tutorial_qt_respeaker std_msgs rospy roscpp -D "Record microphone data"
cd tutorial_qt_respeaker/src
touch tutorial_qt_respeaker_node.py
chmod +x tutorial_qt_respeaker_node.py

Code

Open the tutorial_qt_respeaker_node.py file and add the following code:

#!/usr/bin/env python3
import wave
import rospy
from audio_common_msgs.msg import AudioData


AUDIO_RATE = 16000
AUDIO_CHANNELS = 1
AUDIO_WIDTH = 2


def channel_callback(msg, wf):
wf.writeframes(msg.data)

# main
if __name__ == '__main__':
# call the relevant service
rospy.init_node('audio_record')

wf = wave.open("audio.wav", 'wb')
wf.setnchannels(AUDIO_CHANNELS)
wf.setsampwidth(AUDIO_WIDTH)
wf.setframerate(AUDIO_RATE)

rospy.Subscriber('/qt_respeaker_app/channel0', AudioData, channel_callback, wf)

print("recording...")
rospy.spin()
print("saving...")
wf.close()

This will record processed audio for ASR from channel 0 and save it into audio.wav, which you can later process or listen to it. By default we setup some tuning parameters for noise reduction and automatic gain in config/qt_respeaker_app.yaml which can be modified. If you would like to change the gain of the microphone, you just need to change the line AGCGAIN: 100.0 in config/qt_respeaker_app.yaml.