-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathpepper_talk.py
executable file
·80 lines (57 loc) · 2.46 KB
/
pepper_talk.py
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
#!/usr/bin/env python
# -*- coding: utf-8 -*-
"""
The code includes the section for sending text and "say" commands to Pepper. It receives the text
from another node, sends it to Pepper, and Pepper will articulate it either in the 'ALTextToSpeech'
mode (just saying it) or in the 'ALAnimatedSpeech' mode (accompanied by movements while talking).
Moreover, it publishes information about the time period during which Pepper is talking.
"""
import os
import qi
import argparse
import sys
import rospy
from std_msgs.msg import String
from pepper_ros.msg import PepperTalkTime
class robot:
def __init__(self, session):
## for using ALTextToSpeech
# self.tts=session.service("ALTextToSpeech")
# self.tts.setLanguage("English")
# for using ALAnimatedSpeech (speak while moving)
self.tts=session.service("ALAnimatedSpeech")
# set the local configuration
self.configuration = {"bodyLanguageMode":"contextual"}
self.sub=rospy.Subscriber('/rasa/rasa_response', String, self.give_to_pepper)
self.pub= rospy.Publisher('~talk_time', PepperTalkTime, queue_size=1)
def give_to_pepper(self, data):
pepper_say=data.data
# Get the service ALTextToSpeech.
rospy.loginfo('Pepper say: "%s" ' % pepper_say)
talk_time=PepperTalkTime()
start_stamp=rospy.get_rostime()
## for using ALTextToSpeech
# self.tts.say(str(pepper_say))
# for using ALAnimatedSpeech (speak while moving)
self.tts.say(str(pepper_say),self.configuration)
finish_stamp=rospy.get_rostime()
talk_time.start_stamp=start_stamp
talk_time.finish_stamp=finish_stamp
self.pub.publish(talk_time)
if __name__ == '__main__':
parser = argparse.ArgumentParser()
parser.add_argument("--ip", type=str, default=os.environ.get("NAO_IP",None),
help="Robot IP address.")
parser.add_argument("--port", type=int, default=9559,
help="Naoqi port number")
args = parser.parse_args()
session = qi.Session()
rospy.init_node('pepper_say')
try:
session.connect("tcp://" + args.ip + ":" + str(args.port))
Robot=robot(session)
except RuntimeError:
print ("Can't connect to Naoqi at ip \"" + args.ip + "\" on port " + str(args.port) +".\n"
"Please check your script arguments. Run with -h option for help.")
sys.exit(1)
rospy.spin()