def get_bot_location(self): real_bot_location = "" bot_locations = kb.list_predicates("robot-at") for bot_location in bot_locations: if not bot_location.is_negative: real_bot_location = bot_location.values[1].value return real_bot_location
def go_to_init_location(self): """ Query the Knowledge base for finding the initial location, and move to this position """ robot_loc = kb.list_predicates("robot-at") real_bot_location = "kitchen" for bot_location in robot_loc: if not bot_location.is_negative: real_bot_location = bot_location.values[1].value self.move_robot(None, real_bot_location)
def main(): kb.initialize() print("Predicates ---") for predicate in kb.list_predicates(): print("[" + str(predicate) + "]") print("\nInstances ---") print(str(kb.list_instances()) + "\n") for instance in kb.list_instances(): print("[" + str(instance) + ", " + str(kb.get_instance_type(instance)) + "]") print("\nGoals ---") for goal in kb.list_goals(): print("[" + str(goal) + "]")
#!/usr/bin/env python import rosplan_pytools.controller.knowledge_base as kb import rospy import rosplan_pytools.common.utils as pytools_utils if __name__ == "__main__": rospy.init_node("loud_noise_task_generator") kb.initialize(prefix="/rosplan_knowledge_base") while not rospy.is_shutdown(): respond = False loud_noise_predicates = kb.list_predicates("loud-volume") for loud_noise_pred in loud_noise_predicates: if not loud_noise_pred.is_negative: respond = True if respond and len(kb.list_goals()) == 0: goal = pytools_utils.predicate_maker("asked-all-good", ["person", "subject"], ["personbert", "general"]) kb.add_goal(goal) rospy.loginfo("Goal posted") pytools_utils.plan_and_execute() print("planning done") kb.remove_goal(goal) goal.is_negative = True kb.add_predicate(goal) rospy.sleep(60 * 5) rospy.sleep(5.)
#!/usr/bin/env python import rosplan_pytools.controller.knowledge_base as kb import rospy import rosplan_pytools.common.utils as pytools_utils if __name__ == "__main__": rospy.init_node("kitchen_helping_task_generator") kb.initialize(prefix="/rosplan_knowledge_base") while not rospy.is_shutdown(): respond = False person = "" kitchen_predicates = kb.list_predicates("person-cooking") for kitchen_person in kitchen_predicates: if not kitchen_person.is_negative: respond = True person = kitchen_person.values[0].value if respond: goal = pytools_utils.predicate_maker("asked-all-good", ["person", "topic"], [person, "kitchenhelping"]) kb.add_goal(goal) rospy.loginfo("Goal posted") pytools_utils.plan_and_execute() print("planning done") # Reset goal kb.remove_goal(goal) goal.is_negative = True kb.add_predicate(goal) rospy.sleep(60 * 5) rospy.sleep(5.)
#!/usr/bin/env python import rosplan_pytools.controller.knowledge_base as kb import rospy import rosplan_pytools.common.utils as pytools_utils if __name__ == "__main__": rospy.init_node("doorbell_task_generator") # This task generator will set the to open the goal to open the door kb.initialize(prefix="/rosplan_knowledge_base") while not rospy.is_shutdown(): respond = False dog = "" doorbells = kb.list_predicates("doorbell-ringing") for doorbell in doorbells: if not doorbell.is_negative: respond = True if respond and len(kb.list_goals()) == 0: goal = pytools_utils.predicate_maker("opened-door", "robot", "pepper") kb.add_goal(goal) rospy.loginfo("Goal posted") pytools_utils.plan_and_execute() print("planning done") kb.remove_goal(goal) goal.is_negative = True kb.add_predicate(goal) rospy.sleep(40) rospy.sleep(5.)
#!/usr/bin/env python import rosplan_pytools.controller.knowledge_base as kb import rospy import rosplan_pytools.common.utils as pytools_utils if __name__=="__main__": rospy.init_node("dog_task_generator") kb.initialize(prefix="/rosplan_knowledge_base") while not rospy.is_shutdown(): respond = False dog = "" barking_predicates = kb.list_predicates("dog-barking") for barking_predicate in barking_predicates: if not barking_predicate.is_negative: respond = True dog = barking_predicate.values[0].value if respond and len(kb.list_goals()) == 0: goal = pytools_utils.predicate_maker("dog-interaction", ["robot", "dog"], ["pepper", dog]) kb.add_goal(goal) rospy.loginfo("Goal posted") pytools_utils.plan_and_execute() print("planning done") kb.remove_goal(goal) goal.is_negative = True kb.add_predicate(goal) rospy.sleep(60*5) rospy.sleep(5.)
#!/usr/bin/env python import rosplan_pytools.controller.knowledge_base as kb import rospy import rosplan_pytools.common.utils as pytools_utils if __name__ == "__main__": rospy.init_node("music_task_generator") kb.initialize(prefix="/rosplan_knowledge_base") while not rospy.is_shutdown(): respond = False loud_noise_predicates = kb.list_predicates("hectic-environment") for loud_noise_pred in loud_noise_predicates: if not loud_noise_pred.is_negative: respond = True if respond and len(kb.list_goals()) == 0: goal = pytools_utils.predicate_maker("music-played", ["robot"], ["pepper"]) kb.add_goal(goal) rospy.loginfo("Goal posted") pytools_utils.plan_and_execute() print("planning done") kb.remove_goal(goal) goal.is_negative = True kb.add_predicate(goal) rospy.sleep(60 * 5) rospy.sleep(5.)