6 from contextlib
import contextmanager
12 import tf.transformations
as T
18 from audio_common_msgs.msg
import AudioData
19 from geometry_msgs.msg
import PoseStamped
20 from std_msgs.msg
import Bool, Int32, ColorRGBA
21 from dynamic_reconfigure.server
import Server
23 from pixel_ring
import usb_pixel_ring_v2
26 raise RuntimeError(
"Check the device is connected and recognized")
29 from respeaker_ros.cfg
import RespeakerConfig
30 except Exception
as e:
32 raise RuntimeError(
"Need to run respeaker_gencfg.py first")
43 devnull = os.open(os.devnull, os.O_WRONLY)
53 if devnull
is not None:
63 'AECFREEZEONOFF': (18, 7,
'int', 1, 0,
'rw',
'Adaptive Echo Canceler updates inhibit.',
'0 = Adaptation enabled',
'1 = Freeze adaptation, filter only'),
64 'AECNORM': (18, 19,
'float', 16, 0.25,
'rw',
'Limit on norm of AEC filter coefficients'),
65 'AECPATHCHANGE': (18, 25,
'int', 1, 0,
'ro',
'AEC Path Change Detection.',
'0 = false (no path change detected)',
'1 = true (path change detected)'),
66 'RT60': (18, 26,
'float', 0.9, 0.25,
'ro',
'Current RT60 estimate in seconds'),
67 'HPFONOFF': (18, 27,
'int', 3, 0,
'rw',
'High-pass Filter on microphone signals.',
'0 = OFF',
'1 = ON - 70 Hz cut-off',
'2 = ON - 125 Hz cut-off',
'3 = ON - 180 Hz cut-off'),
68 'RT60ONOFF': (18, 28,
'int', 1, 0,
'rw',
'RT60 Estimation for AES. 0 = OFF 1 = ON'),
69 'AECSILENCELEVEL': (18, 30,
'float', 1, 1e-09,
'rw',
'Threshold for signal detection in AEC [-inf .. 0] dBov (Default: -80dBov = 10log10(1x10-8))'),
70 'AECSILENCEMODE': (18, 31,
'int', 1, 0,
'ro',
'AEC far-end silence detection status. ',
'0 = false (signal detected) ',
'1 = true (silence detected)'),
71 'AGCONOFF': (19, 0,
'int', 1, 0,
'rw',
'Automatic Gain Control. ',
'0 = OFF ',
'1 = ON'),
72 'AGCMAXGAIN': (19, 1,
'float', 1000, 1,
'rw',
'Maximum AGC gain factor. ',
'[0 .. 60] dB (default 30dB = 20log10(31.6))'),
73 'AGCDESIREDLEVEL': (19, 2,
'float', 0.99, 1e-08,
'rw',
'Target power level of the output signal. ',
'[-inf .. 0] dBov (default: -23dBov = 10log10(0.005))'),
74 'AGCGAIN': (19, 3,
'float', 1000, 1,
'rw',
'Current AGC gain factor. ',
'[0 .. 60] dB (default: 0.0dB = 20log10(1.0))'),
75 'AGCTIME': (19, 4,
'float', 1, 0.1,
'rw',
'Ramps-up / down time-constant in seconds.'),
76 'CNIONOFF': (19, 5,
'int', 1, 0,
'rw',
'Comfort Noise Insertion.',
'0 = OFF',
'1 = ON'),
77 'FREEZEONOFF': (19, 6,
'int', 1, 0,
'rw',
'Adaptive beamformer updates.',
'0 = Adaptation enabled',
'1 = Freeze adaptation, filter only'),
78 'STATNOISEONOFF': (19, 8,
'int', 1, 0,
'rw',
'Stationary noise suppression.',
'0 = OFF',
'1 = ON'),
79 'GAMMA_NS': (19, 9,
'float', 3, 0,
'rw',
'Over-subtraction factor of stationary noise. min .. max attenuation'),
80 'MIN_NS': (19, 10,
'float', 1, 0,
'rw',
'Gain-floor for stationary noise suppression.',
'[-inf .. 0] dB (default: -16dB = 20log10(0.15))'),
81 'NONSTATNOISEONOFF': (19, 11,
'int', 1, 0,
'rw',
'Non-stationary noise suppression.',
'0 = OFF',
'1 = ON'),
82 'GAMMA_NN': (19, 12,
'float', 3, 0,
'rw',
'Over-subtraction factor of non- stationary noise. min .. max attenuation'),
83 'MIN_NN': (19, 13,
'float', 1, 0,
'rw',
'Gain-floor for non-stationary noise suppression.',
'[-inf .. 0] dB (default: -10dB = 20log10(0.3))'),
84 'ECHOONOFF': (19, 14,
'int', 1, 0,
'rw',
'Echo suppression.',
'0 = OFF',
'1 = ON'),
85 'GAMMA_E': (19, 15,
'float', 3, 0,
'rw',
'Over-subtraction factor of echo (direct and early components). min .. max attenuation'),
86 'GAMMA_ETAIL': (19, 16,
'float', 3, 0,
'rw',
'Over-subtraction factor of echo (tail components). min .. max attenuation'),
87 'GAMMA_ENL': (19, 17,
'float', 5, 0,
'rw',
'Over-subtraction factor of non-linear echo. min .. max attenuation'),
88 'NLATTENONOFF': (19, 18,
'int', 1, 0,
'rw',
'Non-Linear echo attenuation.',
'0 = OFF',
'1 = ON'),
89 'NLAEC_MODE': (19, 20,
'int', 2, 0,
'rw',
'Non-Linear AEC training mode.',
'0 = OFF',
'1 = ON - phase 1',
'2 = ON - phase 2'),
90 'SPEECHDETECTED': (19, 22,
'int', 1, 0,
'ro',
'Speech detection status.',
'0 = false (no speech detected)',
'1 = true (speech detected)'),
91 'FSBUPDATED': (19, 23,
'int', 1, 0,
'ro',
'FSB Update Decision.',
'0 = false (FSB was not updated)',
'1 = true (FSB was updated)'),
92 'FSBPATHCHANGE': (19, 24,
'int', 1, 0,
'ro',
'FSB Path Change Detection.',
'0 = false (no path change detected)',
'1 = true (path change detected)'),
93 'TRANSIENTONOFF': (19, 29,
'int', 1, 0,
'rw',
'Transient echo suppression.',
'0 = OFF',
'1 = ON'),
94 'VOICEACTIVITY': (19, 32,
'int', 1, 0,
'ro',
'VAD voice activity status.',
'0 = false (no voice activity)',
'1 = true (voice activity)'),
95 'STATNOISEONOFF_SR': (19, 33,
'int', 1, 0,
'rw',
'Stationary noise suppression for ASR.',
'0 = OFF',
'1 = ON'),
96 'NONSTATNOISEONOFF_SR': (19, 34,
'int', 1, 0,
'rw',
'Non-stationary noise suppression for ASR.',
'0 = OFF',
'1 = ON'),
97 'GAMMA_NS_SR': (19, 35,
'float', 3, 0,
'rw',
'Over-subtraction factor of stationary noise for ASR. ',
'[0.0 .. 3.0] (default: 1.0)'),
98 'GAMMA_NN_SR': (19, 36,
'float', 3, 0,
'rw',
'Over-subtraction factor of non-stationary noise for ASR. ',
'[0.0 .. 3.0] (default: 1.1)'),
99 'MIN_NS_SR': (19, 37,
'float', 1, 0,
'rw',
'Gain-floor for stationary noise suppression for ASR.',
'[-inf .. 0] dB (default: -16dB = 20log10(0.15))'),
100 'MIN_NN_SR': (19, 38,
'float', 1, 0,
'rw',
'Gain-floor for non-stationary noise suppression for ASR.',
'[-inf .. 0] dB (default: -10dB = 20log10(0.3))'),
101 'GAMMAVAD_SR': (19, 39,
'float', 1000, 0,
'rw',
'Set the threshold for voice activity detection.',
'[-inf .. 60] dB (default: 3.5dB 20log10(1.5))'),
103 'DOAANGLE': (21, 0,
'int', 359, 0,
'ro',
'DOA angle. Current value. Orientation depends on build configuration.')
116 raise RuntimeError(
"Failed to find Respeaker device")
117 rospy.loginfo(
"Initializing Respeaker device")
123 rospy.loginfo(
"Respeaker device initialized (Version: %s)" % self.
version)
135 data = PARAMETERS[name]
140 raise ValueError(
'{} is read-only'.format(name))
146 payload = struct.pack(b
'iii', data[1], int(value), 1)
148 payload = struct.pack(b
'ifi', data[1], float(value), 0)
150 self.dev.ctrl_transfer(
151 usb.util.CTRL_OUT | usb.util.CTRL_TYPE_VENDOR | usb.util.CTRL_RECIPIENT_DEVICE,
152 0, 0, id, payload, self.
TIMEOUT)
156 data = PARAMETERS[name]
168 response = self.dev.ctrl_transfer(
169 usb.util.CTRL_IN | usb.util.CTRL_TYPE_VENDOR | usb.util.CTRL_RECIPIENT_DEVICE,
170 0, cmd, id, length, self.
TIMEOUT)
172 response = struct.unpack(b
'ii', response.tostring())
177 result = response[0] * (2.**response[1])
182 self.pixel_ring.set_brightness(10)
183 self.pixel_ring.think()
186 self.pixel_ring.set_brightness(20)
187 self.pixel_ring.trace()
190 self.pixel_ring.set_brightness(int(20 * a))
191 self.pixel_ring.set_color(r=int(r*255), g=int(g*255), b=int(b*255))
194 self.
write(
'GAMMAVAD_SR', db)
197 return self.
read(
'VOICEACTIVITY')
201 return self.
read(
'DOAANGLE')
205 return self.dev.ctrl_transfer(
206 usb.util.CTRL_IN | usb.util.CTRL_TYPE_VENDOR | usb.util.CTRL_RECIPIENT_DEVICE,
207 0, 0x80, 0, 1, self.
TIMEOUT)[0]
213 usb.util.dispose_resources(self.
dev)
217 def __init__(self, on_audio, channel=0, suppress_error=True):
229 count = self.pyaudio.get_device_count()
230 rospy.logdebug(
"%d audio devices found" % count)
231 for i
in range(count):
232 info = self.pyaudio.get_device_info_by_index(i)
233 name = info[
"name"].encode(
"utf-8")
234 chan = info[
"maxInputChannels"]
235 rospy.logdebug(
" - %d: %s" % (i, name))
236 if name.lower().find(
"respeaker") >= 0:
239 rospy.loginfo(
"Found %d: %s (channels: %d)" % (i, name, chan))
242 rospy.logwarn(
"Failed to find respeaker device by name. Using default input")
243 info = self.pyaudio.get_default_input_device_info()
244 self.
channels = info[
"maxInputChannels"]
248 rospy.logwarn(
"%d channel is found for respeaker" % self.
channels)
249 rospy.logwarn(
"You may have to update firmware.")
253 input=
True, start=
False,
254 format=pyaudio.paInt16,
257 frames_per_buffer=1024,
271 self.pyaudio.terminate()
277 data = np.fromstring(in_data, dtype=np.int16)
278 chunk_per_channel = len(data) / self.
channels 279 data = np.reshape(data, (chunk_per_channel, self.
channels))
280 chan_data = data[:, self.
channel]
283 return None, pyaudio.paContinue
286 if self.stream.is_stopped():
287 self.stream.start_stream()
290 if self.stream.is_active():
291 self.stream.stop_stream()
305 suppress_pyaudio_error = rospy.get_param(
"~suppress_pyaudio_error",
True)
314 self.
pub_vad = rospy.Publisher(
"is_speeching", Bool, queue_size=1, latch=
True)
315 self.
pub_doa_raw = rospy.Publisher(
"sound_direction", Int32, queue_size=1, latch=
True)
316 self.
pub_doa = rospy.Publisher(
"sound_localization", PoseStamped, queue_size=1, latch=
True)
317 self.
pub_audio = rospy.Publisher(
"audio", AudioData, queue_size=10)
325 self.
speech_prefetch * self.respeaker_audio.rate * self.respeaker_audio.bitdepth / 8.0)
327 self.respeaker_audio.start()
335 self.respeaker.close()
341 self.respeaker_audio.stop()
350 for name
in config.keys():
351 config[name] = self.respeaker.read(name)
354 for name, value
in config.items():
355 prev_val = self.
config[name]
356 if prev_val != value:
357 self.respeaker.write(name, value)
362 self.respeaker.set_led_color(r=msg.r, g=msg.g, b=msg.b, a=msg.a)
363 if self.
timer_led and self.timer_led.is_alive():
364 self.timer_led.shutdown()
365 self.
timer_led = rospy.Timer(rospy.Duration(3.0),
366 lambda e: self.respeaker.set_led_trace(),
370 self.pub_audio.publish(AudioData(data=data))
380 stamp = event.current_real
or rospy.Time.now()
381 is_voice = self.respeaker.is_voice()
382 doa_rad = math.radians(self.respeaker.direction - 180.0)
385 doa = math.degrees(doa_rad)
389 self.pub_vad.publish(Bool(data=is_voice))
394 self.pub_doa_raw.publish(Int32(data=doa))
399 msg.header.stamp = stamp
400 ori = T.quaternion_from_euler(math.radians(doa), 0, 0)
403 msg.pose.orientation.w = ori[0]
404 msg.pose.orientation.x = ori[1]
405 msg.pose.orientation.y = ori[2]
406 msg.pose.orientation.z = ori[3]
407 self.pub_doa.publish(msg)
418 duration = 8.0 * len(buf) * self.respeaker_audio.bitwidth
419 duration = duration / self.respeaker_audio.rate / self.respeaker_audio.bitdepth
420 rospy.loginfo(
"Speech detected for %.3f seconds" % duration)
423 self.pub_speech_audio.publish(AudioData(data=buf))
426 if __name__ ==
'__main__':
427 rospy.init_node(
"respeaker_node")
def on_config(self, config, level)
static double shortest_angular_distance(double from, double to)
def set_vad_threshold(self, db)
def __init__(self, on_audio, channel=0, suppress_error=True)
def write(self, name, value)
def on_timer(self, event)
def ignore_stderr(enable=True)
def on_status_led(self, msg)
def stream_callback(self, in_data, frame_count, time_info, status)
def set_led_color(self, r, g, b, a)