Skip to content

Commit

Permalink
listo
Browse files Browse the repository at this point in the history
  • Loading branch information
maxfloresv authored Dec 14, 2022
1 parent 2b05966 commit 9f3b6ca
Showing 1 changed file with 28 additions and 10 deletions.
38 changes: 28 additions & 10 deletions voice2text.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,14 @@

import rospy
from std_msgs.msg import String
from std_msgs.msg import String, Empty
from sensor_msgs.msg import Joy
import cv2
import time
import speech_recognition as sr
import sys
import wikipediaapi

wiki = wikipediaapi.Wikipedia('es')

# Mientras run=True, corre el programa
run = True
Expand All @@ -17,7 +21,8 @@ def __init__(self, args):

# Publisher de voz
self.pub_voz = rospy.Publisher("/duckiebot/voz/v2t", String, queue_size=10)
self.pub_tiempo = rospy.Publisher("/duckiebot/voz/tiempo", String, queue_size=1)
self.pub_tiempo = rospy.Publisher("/duckiebot/voz/tiempo", String, queue_size=10)
self.pub_wiki = rospy.Publisher("/duckiebot/voz/wiki", String, queue_size=10)

# Subscribers
rospy.Subscriber("/duckiebot/joy", Joy, self.callback_control)
Expand All @@ -29,7 +34,7 @@ def __init__(self, args):
self.A = 0
self.X = 0

def callback(self, auto=False):
def callback(self, instruccion=None, auto=False):
# Modifico los valores globales
global run, active

Expand All @@ -41,22 +46,34 @@ def callback(self, auto=False):
if (self.A == 1 and not active) or auto:
active = True
with sr.Microphone() as source:
print("Quack quack...") # que lo diga
if not auto:
print("Quack quack...")
else:
print("Quack %s..." % instruccion)
audio = self.r.listen(source, None, 1.5)

msg = String()

try:
text = self.r.recognize_google(audio, language='es-ES')
print("Lo quack dijiste fue:", str(text))
msg = String()
msg.data = str(text)

# Si se llama desde el programa, es tiempo (en segundos)
if auto:
self.pub_tiempo.publish(msg)
# Sino, es probablemente una instruccion
if auto and instruccion != None:
if instruccion == "tiempo":
self.pub_tiempo.publish(msg)
elif instruccion == "buscar":
pagina = wiki.page(msg.data)
resumen = pagina.summary[0:60]
msg.data = resumen
self.pub_wiki.publish(msg)
else:
self.pub_voz.publish(msg)
except Exception as e:
# Si no capta la instruccion, debe volver a pedir input
if instruccion == "tiempo":
self.pub_tiempo.publish(msg)

print("No quackche", str(e))

active = False
Expand All @@ -68,8 +85,9 @@ def callback_control(self, msg):
self.X = buttons[2]

def callback_req(self, msg):
self.callback(True)
inst = msg.data

self.callback(inst, True)

def main():
# Nodo local del PC
Expand Down

0 comments on commit 9f3b6ca

Please sign in to comment.