Skip to content

Commit

Permalink
[Receptionist Code clean up]
Browse files Browse the repository at this point in the history
  • Loading branch information
Julislz committed Feb 29, 2024
1 parent e4a6352 commit 80719d1
Show file tree
Hide file tree
Showing 11 changed files with 65 additions and 231 deletions.
24 changes: 5 additions & 19 deletions demos/pycram_receptionist_demo/M2_Demo.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,9 @@


def demo_ms2(area):

with real_robot:

# declare variables for humans
host = HumanDescription("Yannis", fav_drink="Tea")
guest1 = HumanDescription("guest1")
Expand All @@ -58,23 +60,20 @@ def demo_ms2(area):
# look at guest and introduce
giskardpy.move_head_to_human()
TalkingMotion("Hello, i am Toya and my favorite drink is oil. What about you, talk to me?").resolve().perform()

rospy.sleep(1)

# signal to start listening
pub_nlp.publish("start listening")

#wait for human to say something
rospy.sleep(13)
# wait for human to say something
rospy.sleep(15)

# guest_data format is = ["name", "drink"]
# guest_data format is = ['person infos: "name', 'drink"']
guest_data = get_guest_info("1.0")
print("guest data: " + str(guest_data))
while guest_data == ['person_infos: "No name saved under this ID!"']:
talk_error("no name")
rospy.sleep(13)
guest_data = get_guest_info("1.0")
print("guest data: " + str(guest_data))

# set heard name and drink of guest
guest1.set_name(guest_data[0][13:])
Expand All @@ -98,12 +97,10 @@ def demo_ms2(area):
rospy.sleep(5)
NavigateAction([pose_kitchen_to_couch]).resolve().perform()
NavigateAction([pose_couch]).resolve().perform()
rospy.sleep(2)
TalkingMotion("Welcome to the living room").resolve().perform()
rospy.sleep(1)
elif area == 'from_couch':
rospy.loginfo("Navigating now")
TalkingMotion("navigating to kitchen, please step away").resolve().perform()
rospy.sleep(5)
NavigateAction([pose_from_couch]).resolve().perform()
NavigateAction([pose_home]).resolve().perform()
Expand All @@ -112,18 +109,7 @@ def demo_ms2(area):
TalkingMotion("not navigating").resolve().perform()
rospy.sleep(1)


introduce(guest1.name, guest1.fav_drink, host.name, host.fav_drink)
#TalkingMotion("End of demo").resolve().perform()


def nav_test():
with real_robot:
robot_orientation = axis_angle_to_quaternion([0, 0, 1], 90)
test_pose1 = Pose([4.2, 3, 0], robot_orientation)
test_pose = Pose([3, 5, 0], [0, 0, 0, 1])
moveBase.queryPoseNav(test_pose1)
moveBase.queryPoseNav(test_pose)


# demo_test('from_couch')
Expand Down
131 changes: 0 additions & 131 deletions demos/pycram_receptionist_demo/MS2_example-v.py

This file was deleted.

31 changes: 6 additions & 25 deletions demos/pycram_receptionist_demo/School_Demo.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
from pycram.designators.action_designator import DetectAction, NavigateAction
from pycram.designators.motion_designator import TalkingMotion
# from demos.pycram_receptionist_demo.utils.misc import *
from demos.pycram_receptionist_demo.utils.misc import *
from pycram.helper import axis_angle_to_quaternion
from pycram.process_module import real_robot
import pycram.external_interfaces.giskard as giskardpy
Expand Down Expand Up @@ -42,7 +42,7 @@
data_received = False


def talk_request(data: String):
def talk_request_school(data: String):
"""
callback function that takes the data from nlp (name and drink) and lets the robot talk
:param data: String "name drink"
Expand All @@ -55,30 +55,19 @@ def talk_request(data: String):
data_received = True


def talk_error(data):
"""
callback function if no name/drink was heard
"""

error_msgs = "i could not hear you, please repeat"
TalkingMotion(error_msgs).resolve().perform()
pub_nlp.publish("start listening")


def demo_test(area):
with real_robot:
global data_received
data_received = False
print("start demo")

# look for human
DetectAction(technique='human', state='start').resolve().perform()

rospy.loginfo("human detected")

# look at guest and introduction
giskardpy.move_head_to_human()
TalkingMotion("Hello, i am Toya and my favorite drink is oil. What about you, talk to me?").resolve().perform()

rospy.sleep(1)

# signal to start listening
Expand All @@ -90,7 +79,7 @@ def demo_test(area):
# get name and drink
rospy.Subscriber("nlp_feedback", Bool, talk_error)

rospy.Subscriber("nlp_out", String, talk_request)
rospy.Subscriber("nlp_out", String, talk_request_school)

while not data_received:
rospy.sleep(0.5)
Expand Down Expand Up @@ -119,28 +108,20 @@ def demo_test(area):
rospy.sleep(1)
TalkingMotion("Welcome to the living room").resolve().perform()
TalkingMotion("take a seat").resolve().perform()

elif area == 'from_couch':
rospy.loginfo("Navigating now")
rospy.sleep(3)
NavigateAction([pose_from_couch]).resolve().perform()
NavigateAction([pose_home]).resolve().perform()

else:
rospy.loginfo("in else")
TalkingMotion("not navigating").resolve().perform()
rospy.sleep(3)
print("end")

TalkingMotion("End of demo").resolve().perform()


def nav_test():
with real_robot:
robot_orientation = axis_angle_to_quaternion([0, 0, 1], 90)
test_pose1 = Pose([4.2, 3, 0], robot_orientation)
test_pose = Pose([3, 5, 0], [0, 0, 0, 1])
moveBase.queryPoseNav(test_pose1)
moveBase.queryPoseNav(test_pose)


# demo_test('from_couch')
demo_test('to_couch')
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ def demo_test():
pub_nlp.publish("start listening")
rospy.sleep(5)
#asyncron??
# TODO: test on real HSR

guest_data = get_guest_info("3.0")
print("guest data: " + str(guest_data))
while guest_data == "No name saved under this ID!":
Expand Down
27 changes: 3 additions & 24 deletions demos/pycram_receptionist_demo/tests/nlp_planning.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
from pycram.designators.action_designator import DetectAction, NavigateAction
from pycram.designators.motion_designator import TalkingMotion
from pycram.fluent import Fluent
#from demos.pycram_receptionist_demo.utils.misc import *
from demos.pycram_receptionist_demo.utils.misc import *
from pycram.helper import axis_angle_to_quaternion
from pycram.process_module import real_robot
import pycram.external_interfaces.giskard as giskardpy
Expand Down Expand Up @@ -32,27 +32,6 @@

pub_nlp = rospy.Publisher('/startListener', String, queue_size=10)

def talk_error(data):
"""
callback function if no name/drink was heard
"""
rospy.loginfo(data)
rospy.loginfo("in callback error")
error_msgs = "i could not hear you, please repeat"
TalkingMotion(error_msgs).resolve().perform()
rospy.sleep(3)
pub_nlp.publish("start listening")

def talk_request(data: String):
"""
callback function that takes the data from nlp (name and drink) and lets the robot talk
:param data: String "name drink"
"""
rospy.loginfo("in callback success")
name_drink = data.data.split(" ")
talk_actions.name_drink_talker(name_drink)
rospy.loginfo("nlp data:" + name_drink[0] + " " + name_drink[1])


def test():
with real_robot:
Expand All @@ -71,10 +50,10 @@ def test():
rospy.Subscriber("nlp_feedback", Bool, talk_error)

# receives name and drink via topic
rospy.Subscriber("nlp_out", String, talk_request)
rospy.Subscriber("nlp_out", String, talk_request_nlp)

while True:
print("HEllo")
print("Hello")


if __name__ == '__main__':
Expand Down
30 changes: 3 additions & 27 deletions demos/pycram_receptionist_demo/tests/perception_humans.py
Original file line number Diff line number Diff line change
Expand Up @@ -26,30 +26,14 @@
# carefull that u spawn the correct kitchen
kitchen = Object("kitchen", "environment", "kitchen.urdf")
giskardpy.init_giskard_interface()
#RobotStateUpdater("/tf", "/giskard_joint_states")



def test():
with real_robot:
guest1 = HumanDescription("x")
# print("...................... nothing" )
guest1.human_pose.set_value(False)
if not guest1.human_pose.get_value():
print("wrong? " + str(guest1.human_pose))

if guest1.human_pose.get_value():
print("right? " + str(guest1.human_pose))

print("----------------------------------")
DetectAction(technique='human', state='start').resolve().perform()

if not guest1.human_pose.get_value():
print("wrong? " + str(guest1.human_pose))

if guest1.human_pose.get_value():
print("right? " + str(guest1.human_pose))



rospy.loginfo("human detected")

print("---------- " + "start")
Expand All @@ -67,13 +51,5 @@ def test():
print("end")










if __name__ == '__main__':
test()
test()
Loading

0 comments on commit 80719d1

Please sign in to comment.