From f15aaea63e8dcc3a44494f71813ef76bfc7c3d95 Mon Sep 17 00:00:00 2001 From: juschulz Date: Fri, 9 Feb 2024 15:24:32 +0100 Subject: [PATCH] [HumanDescription fix] callback function changed to right type so that subscriber works now (hopefully) --- .../tests/Ms2_testable_stuff.py | 10 +++++++--- .../tests/perception_humans.py | 20 +++++++++++++++++-- src/pycram/designators/object_designator.py | 7 +++++-- 3 files changed, 30 insertions(+), 7 deletions(-) diff --git a/demos/pycram_receptionist_demo/tests/Ms2_testable_stuff.py b/demos/pycram_receptionist_demo/tests/Ms2_testable_stuff.py index 006427af2..793571e46 100644 --- a/demos/pycram_receptionist_demo/tests/Ms2_testable_stuff.py +++ b/demos/pycram_receptionist_demo/tests/Ms2_testable_stuff.py @@ -48,15 +48,17 @@ def demo_test(area): with real_robot: print("start demo") host = HumanDescription("Bob", fav_drink="Coffee") + host.human_pose.set_value(False) guest1 = HumanDescription("guest1") + guest1.human_pose.set_value(False) # Perception, detect first guest DetectAction(technique='human', state='start').resolve().perform() # While loop, human is detected - #while not guest1.human_pose: - # TalkingMotion("Please step in front of me").resolve.perform() - # rospy.sleep(5) + while not guest1.human_pose.get_value(): + TalkingMotion("Please step in front of me").resolve.perform() + rospy.sleep(5) rospy.loginfo("human detected") @@ -97,6 +99,8 @@ def demo_test(area): # stop perceiving human DetectAction(technique='human', state='stop').resolve().perform() + guest1.human_pose.set_value(False) + host.human_pose.set_value(False) rospy.loginfo("Navigating now") TalkingMotion("navigating to couch area now, please step away").resolve().perform() diff --git a/demos/pycram_receptionist_demo/tests/perception_humans.py b/demos/pycram_receptionist_demo/tests/perception_humans.py index 03d08064b..59a2298ba 100644 --- a/demos/pycram_receptionist_demo/tests/perception_humans.py +++ b/demos/pycram_receptionist_demo/tests/perception_humans.py @@ -30,17 +30,33 @@ def test(): with real_robot: - print("...................... nothing" ) + 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") rospy.loginfo("sleeping now") - rospy.sleep(10) + rospy.sleep(5) rospy.loginfo("sleep done stopping now") diff --git a/src/pycram/designators/object_designator.py b/src/pycram/designators/object_designator.py index c32f66c93..3301e1a41 100644 --- a/src/pycram/designators/object_designator.py +++ b/src/pycram/designators/object_designator.py @@ -3,6 +3,8 @@ import rospy import sqlalchemy.orm +from geometry_msgs.msg import PoseStamped + from ..bullet_world import BulletWorld, Object as BulletWorldObject from ..designator import DesignatorDescription, ObjectDesignatorDescription from ..orm.base import ProcessMetaData @@ -196,7 +198,7 @@ def __init__(self, name, fav_drink: Optional = None): self.name = name self.fav_drink = fav_drink # self.shirt_color = shirt_color # self.gender = gender - self.human_pose_sub = rospy.Subscriber("/human_pose", String, self.human_pose_cb) + self.human_pose_sub = rospy.Subscriber("/human_pose", PoseStamped, self.human_pose_cb) def human_pose_cb(self, HumanPoseMsg): """ @@ -204,7 +206,8 @@ def human_pose_cb(self, HumanPoseMsg): sets the attribute human_pose when someone (e.g. Perception/Robokudo) publishes on the topic :param HumanPoseMsg: received message """ - self.human_pose.set_value(HumanPoseMsg.data) + rospy.loginfo("in callback") + self.human_pose.set_value(True) def set_name(self, new_name): """