25 import sounddevice
as sd
26 from mmap
import MAP_SHARED
30 from ros_vosk.msg
import speech_recognition
31 from std_msgs.msg
import String, Bool
33 import vosk_ros_model_downloader
as downloader
37 model_name = rospy.get_param(
'vosk/model',
"vosk-model-small-en-us-0.15")
39 rospack = rospkg.RosPack()
41 package_path = rospack.get_path(
'ros_vosk')
43 models_dir = os.path.join(package_path,
'models')
44 model_path = os.path.join(models_dir, model_name)
46 if not os.path.exists(model_path):
47 print (f
"model '{model_name}' not found in '{models_dir}'! Please use the GUI to download it or configure an available model...")
48 model_downloader = downloader.model_downloader()
49 model_downloader.execute()
50 model_name = model_downloader.model_to_download
52 if not rospy.has_param(
'vosk/model'):
53 rospy.set_param(
'vosk/model', model_name)
59 self.
pub_vosk = rospy.Publisher(
'speech_recognition/vosk_result',speech_recognition, queue_size=10)
60 self.
pub_final = rospy.Publisher(
'speech_recognition/final_result',String, queue_size=10)
61 self.
pub_partial = rospy.Publisher(
'speech_recognition/partial_result',String, queue_size=10)
63 self.
rate = rospy.Rate(100)
67 self.
msg = speech_recognition()
69 self.
q = queue.Queue()
73 rospy.logfatal(
'No input device found')
74 raise ValueError(
'No input device found, device number == -1')
80 rospy.set_param(
'vosk/sample_rate', self.
samplerate)
82 self.
model = vosk.Model(model_path)
89 rospy.logwarn(
"Shutting down VOSK speech recognition node...")
94 print(status, file=sys.stderr)
95 self.
q.put(bytes(indata))
108 rospy.logdebug(
'Started recording')
111 print(
"Vosk is ready to listen!")
113 isRecognized_partially =
False
116 while not rospy.is_shutdown():
127 if rec.AcceptWaveform(data):
130 result = rec.FinalResult()
132 diction = json.loads(result)
133 lentext = len(diction[
"text"])
136 result_text = diction[
"text"]
137 rospy.loginfo(result_text)
145 result_partial = rec.PartialResult()
146 if (len(result_partial) > 20):
148 isRecognized_partially =
True
149 partial_dict = json.loads(result_partial)
150 partial = partial_dict[
"partial"]
152 if (isRecognized
is True):
154 self.
msg.isSpeech_recognized =
True
155 self.
msg.time_recognized = rospy.Time.now()
156 self.
msg.final_result = result_text
157 self.
msg.partial_result =
"unk"
164 elif (isRecognized_partially
is True):
166 self.
msg.isSpeech_recognized =
False
167 self.
msg.time_recognized = rospy.Time.now()
168 self.
msg.final_result =
"unk"
169 self.
msg.partial_result = partial
174 isRecognized_partially =
False
178 except Exception
as e:
179 exit(type(e).__name__ +
': ' + str(e))
180 except KeyboardInterrupt:
181 rospy.loginfo(
"Stopping the VOSK speech recognition node...")
183 print(
"node terminated")
185 if __name__ ==
'__main__':
187 rospy.init_node(
'vosk', anonymous=
False)
189 rec.speech_recognize()
190 except (KeyboardInterrupt, rospy.ROSInterruptException)
as e:
191 rospy.logfatal(
"Error occurred! Stopping the vosk speech recognition node...")
193 print(
"node terminated")