forked from ilabsweden/pepperchat
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathmodule_dialogue.py
More file actions
225 lines (190 loc) · 7.56 KB
/
module_dialogue.py
File metadata and controls
225 lines (190 loc) · 7.56 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
# -*- coding: utf-8 -*-
###########################################################
# This module implements the main dialogue functionality for Pepper.
#
# Syntax:
# python scriptname --pip <ip> --pport <port>
#
# --pip <ip>: specify the ip of your robot (without specification it will use the ROBOT_IP defined below
#
# Author: Johannes Bramauer, Vienna University of Technology and Erik Billing, University of Skovde
# Created: May 30, 2018 and updated spring 2022.
# License: MIT
###########################################################
ROBOT_PORT = 9559 # Robot
ROBOT_IP = "pepper.local" # Pepper default
AUTODEC = True
from optparse import OptionParser
import re
import naoqi
import time
import sys
import codecs
from naoqi import ALProxy
participantId = raw_input('Participant ID: ')
from oaichat.oaiclient import OaiClient
chatbot = OaiClient(user=participantId)
chatbot.reset()
class DialogueSpeechReceiverModule(naoqi.ALModule):
"""
Use this object to get call back from the ALMemory of the naoqi world.
Your callback needs to be a method with two parameter (variable name, value).
"""
def __init__( self, strModuleName, strNaoIp ):
self.autodec = AUTODEC
self.misunderstandings=0
self.log = codecs.open('dialogue.log','a',encoding='utf-8')
try:
naoqi.ALModule.__init__(self, strModuleName )
self.BIND_PYTHON( self.getName(),"callback" )
self.strNaoIp = strNaoIp
#self.session = qi.Session()
except BaseException, err:
print( "ERR: ReceiverModule: loading error: %s" % str(err) )
def __del__( self ):
print( "INF: ReceiverModule.__del__: cleaning everything" )
self.stop()
def start( self ):
self.memory = naoqi.ALProxy("ALMemory", self.strNaoIp, ROBOT_PORT)
self.memory.subscribeToEvent("SpeechRecognition", self.getName(), "processRemote")
print( "INF: ReceiverModule: started!" )
try:
self.posture = ALProxy("ALRobotPosture", self.strNaoIp, ROBOT_PORT)
self.aup = ALProxy("ALAnimatedSpeech", self.strNaoIp, ROBOT_PORT)
except RuntimeError:
print ("Can't connect to Naoqi at ip \"" + self.strNaoIp + "\" on port " + str(ROBOT_PORT) +".\n"
"Please check your script arguments. Run with -h option for help.")
def stop( self ):
print( "INF: ReceiverModule: stopping..." )
self.memory.unsubscribe(self.getName())
print( "INF: ReceiverModule: stopped!" )
def version( self ):
return "2.0"
def encode(self,s):
s = s.replace(u'å','a').replace(u'ä','a').replace(u'ö','o')
s = s.replace(u'Skovde','Schoe the')
return codecs.encode(s,'ascii','ignore')
def processRemote(self, signalName, message):
self.log.write('INP: ' + message + '\n')
if message == 'error':
print('Input not recognized, continue listen')
return
if self.autodec:
#always disable to not detect its own speech
SpeechRecognition.disableAutoDetection()
#and stop if it was already recording another time
SpeechRecognition.pause()
# received speech recognition result
print("INPUT RECOGNIZED: \n"+message)
#computing answer
if message=='error':
self.misunderstandings +=1
if self.misunderstandings ==1:
answer="I didn't understand, can you repeat?"
elif self.misunderstandings == 2:
answer="Sorry I didn't get it, can you say it one more time?"
elif self.misunderstandings == 3:
answer="Today I'm having troubles uderstanding what you are saying, I'm sorry"
else:
answer="Please repeat that."
print('ERROR, DEFAULT ANSWER:\n'+answer)
else:
self.misunderstandings = 0
answer = self.encode(chatbot.respond(message))
print('DATA RECEIVED AS ANSWER:\n'+answer)
#text to speech the answer
self.log.write('ANS: ' + answer + '\n')
self.aup.say(answer)
self.react(answer)
#time.sleep(2)
if self.autodec:
print("starting service speech-rec again")
SpeechRecognition.start()
print("autodec enabled")
SpeechRecognition.enableAutoDetection()
else:
#asking the Speech Recognition to LISTEN AGAIN
SpeechRecognition.startRecording()
def react(self,s):
if re.match(".*I.*sit down.*",s): # Sitting down
self.posture.goToPosture("Sit",1.0)
elif re.match(".*I.*stand up.*",s): # Standing up
self.posture.goToPosture("Stand",1.0)
elif re.match(".*I.*(lie|lyi).*down.*",s): # Lying down
self.posture.goToPosture("LyingBack",1.0)
def main():
""" Main entry point
"""
parser = OptionParser()
parser.add_option("--pip",
help="Parent broker port. The IP address or your robot",
dest="pip")
parser.add_option("--pport",
help="Parent broker port. The port NAOqi is listening to",
dest="pport",
type="int")
parser.set_defaults(
pip=ROBOT_IP,
pport=ROBOT_PORT)
(opts, args_) = parser.parse_args()
pip = opts.pip
pport = opts.pport
# We need this broker to be able to construct
# NAOqi modules and subscribe to other modules
# The broker must stay alive until the program exists
myBroker = naoqi.ALBroker("myBroker",
"0.0.0.0", # listen to anyone
0, # find a free port and use it
pip, # parent broker IP
pport) # parent broker port
try:
p = ALProxy("DialogueSpeechReceiver")
p.exit() # kill previous instance
except:
pass
#AutonomousLife = ALProxy('ALAutonomousLife')
#AutonomousLife.setState('solitary')
# Reinstantiate module
# Warning: ReceiverModule must be a global variable
# The name given to the constructor must be the name of the
# variable
global DialogueSpeechReceiver
DialogueSpeechReceiver = DialogueSpeechReceiverModule("DialogueSpeechReceiver", pip)
DialogueSpeechReceiver.start()
global SpeechRecognition
SpeechRecognition = ALProxy("SpeechRecognition")
SpeechRecognition.start()
#SpeechRecognition.calibrate()
if(AUTODEC==False):
print("False, auto-detection not available")
#one-shot recording for at least 5 seconds
SpeechRecognition = ALProxy("SpeechRecognition")
SpeechRecognition.start()
SpeechRecognition.setHoldTime(5)
SpeechRecognition.setIdleReleaseTime(1.7)
SpeechRecognition.setMaxRecordingDuration(10)
SpeechRecognition.startRecording()
else:
print("True, auto-detection selected")
# auto-detection
SpeechRecognition = ALProxy("SpeechRecognition")
SpeechRecognition.start()
SpeechRecognition.setHoldTime(2.5)
SpeechRecognition.setIdleReleaseTime(1.0)
SpeechRecognition.setMaxRecordingDuration(10)
SpeechRecognition.setLookaheadDuration(0.5)
#SpeechRecognition.setLanguage("de-de")
#SpeechRecognition.calibrate()
SpeechRecognition.setAutoDetectionThreshold(10)
SpeechRecognition.enableAutoDetection()
#SpeechRecognition.startRecording()
try:
while True:
time.sleep(1)
except KeyboardInterrupt:
print
print("Interrupted by user, shutting down")
myBroker.shutdown()
sys.exit(0)
if __name__ == "__main__":
main()