Skip to content

Commit

Permalink
Merge pull request #27 from 708yamaguchi/respeaker-multi-pr1040
Browse files Browse the repository at this point in the history
  • Loading branch information
708yamaguchi authored Aug 9, 2022
2 parents a8981f8 + 074a809 commit 4079d98
Show file tree
Hide file tree
Showing 2 changed files with 42 additions and 20 deletions.
47 changes: 28 additions & 19 deletions respeaker_ros/scripts/respeaker_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,13 @@
import sys
import time
from audio_common_msgs.msg import AudioData
from audio_common_msgs.msg import AudioInfo
enable_audio_info = True
try:
from audio_common_msgs.msg import AudioInfo
except Exception as e:
rospy.logwarn('audio_common_msgs/AudioInfo message is not exists.'
' AudioInfo message will not be published.')
enable_audio_info = False
from geometry_msgs.msg import PoseStamped
from std_msgs.msg import Bool, Int32, ColorRGBA
from dynamic_reconfigure.server import Server
Expand Down Expand Up @@ -332,8 +338,9 @@ def __init__(self):
self.pub_doa_raw = rospy.Publisher("sound_direction", Int32, queue_size=1, latch=True)
self.pub_doa = rospy.Publisher("sound_localization", PoseStamped, queue_size=1, latch=True)
self.pub_audio = rospy.Publisher("audio", AudioData, queue_size=10)
self.pub_audio_info = rospy.Publisher("audio_info", AudioInfo,
queue_size=1, latch=True)
if enable_audio_info is True:
self.pub_audio_info = rospy.Publisher("audio_info", AudioInfo,
queue_size=1, latch=True)
self.pub_audio_raw_info = rospy.Publisher("audio_info_raw", AudioInfo,
queue_size=1, latch=True)
self.pub_speech_audio = rospy.Publisher("speech_audio", AudioData, queue_size=10)
Expand All @@ -357,13 +364,14 @@ def __init__(self):
self.sub_led = rospy.Subscriber("status_led", ColorRGBA, self.on_status_led)

# processed audio for ASR
info_msg = AudioInfo(
channels=1,
sample_rate=self.respeaker_audio.rate,
sample_format='S16LE',
bitrate=self.respeaker_audio.rate * self.respeaker_audio.bitdepth,
coding_format='WAVE')
self.pub_audio_info.publish(info_msg)
if enable_audio_info is True:
info_msg = AudioInfo(
channels=1,
sample_rate=self.respeaker_audio.rate,
sample_format='S16LE',
bitrate=self.respeaker_audio.rate * self.respeaker_audio.bitdepth,
coding_format='WAVE')
self.pub_audio_info.publish(info_msg)

if self.n_channel > 1:
# The respeaker has 4 microphones.
Expand All @@ -387,21 +395,22 @@ def __init__(self):
self.pub_audio_merged_playback = rospy.Publisher(
"audio_merged_playback", AudioData,
queue_size=10)
info_raw_msg = AudioInfo(
channels=self.n_channel - 2,
sample_rate=self.respeaker_audio.rate,
sample_format='S16LE',
bitrate=(self.respeaker_audio.rate *
self.respeaker_audio.bitdepth),
coding_format='WAVE')
self.pub_audio_raw_info.publish(info_raw_msg)
if enable_audio_info is True:
info_raw_msg = AudioInfo(
channels=self.n_channel - 2,
sample_rate=self.respeaker_audio.rate,
sample_format='S16LE',
bitrate=(self.respeaker_audio.rate *
self.respeaker_audio.bitdepth),
coding_format='WAVE')
self.pub_audio_raw_info.publish(info_raw_msg)

self.speech_audio_raw_buffer = b""
self.speech_raw_prefetch_buffer = b""
self.pub_speech_audio_raw = rospy.Publisher(
"speech_audio_raw", AudioData, queue_size=10)
self.speech_raw_prefetch_bytes = int(
self.n_channel - 2
(self.n_channel - 2)
* self.speech_prefetch
* self.respeaker_audio.rate
* self.respeaker_audio.bitdepth / 8.0)
Expand Down
15 changes: 14 additions & 1 deletion respeaker_ros/scripts/speech_to_text.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,8 @@

from __future__ import division

import sys

import actionlib
import rospy
try:
Expand All @@ -14,7 +16,13 @@
import numpy as np
from actionlib_msgs.msg import GoalStatus, GoalStatusArray
from audio_common_msgs.msg import AudioData
from audio_common_msgs.msg import AudioInfo
enable_audio_info = True
try:
from audio_common_msgs.msg import AudioInfo
except Exception as e:
rospy.logwarn('audio_common_msgs/AudioInfo message is not exists.'
' AudioInfo message will not be published.')
enable_audio_info = False
from sound_play.msg import SoundRequest, SoundRequestAction, SoundRequestGoal
from speech_recognition_msgs.msg import SpeechRecognitionCandidates

Expand All @@ -24,6 +32,11 @@ def __init__(self):
# format of input audio data
audio_info_topic_name = rospy.get_param('~audio_info', '')
if len(audio_info_topic_name) > 0:
if enable_audio_info is False:
rospy.logerr(
'audio_common_msgs/AudioInfo message is not exists.'
' Giving ~audio_info is not valid in your environment.')
sys.exit(1)
rospy.loginfo('Extract audio info params from {}'.format(
audio_info_topic_name))
audio_info_msg = rospy.wait_for_message(
Expand Down

0 comments on commit 4079d98

Please sign in to comment.