def build_tree(self): eva_behavior_tree = \ owyl.repeatAlways( owyl.selector( owyl.sequence( self.is_scripted_performance_system_on(), self.sync_variables(), ########## Main Events ########## owyl.selector( self.someone_arrived(), self.someone_left(), self.interact_with_people(), self.nothing_is_happening() ) ), # Turn on scripted performances # This point is reached only when scripting is turned off. owyl.sequence( self.idle_spin(), self.is_scripted_performance_system_off(), self.start_scripted_performance_system() ) ) ) return owyl.visit(eva_behavior_tree, blackboard=self.blackboard)
def interact_with_people(self) : tree = owyl.sequence( self.is_face_target(), owyl.selector( ##### Start A New Interaction ##### owyl.sequence( owyl.selector( self.is_not_interacting_with_someone(), owyl.sequence( self.is_more_than_one_face_target(), self.is_time_to_change_face_target() ) ), self.select_a_face_target(), self.record_start_time(variable="interact_with_face_target_since"), self.interact_with_face_target(id="current_face_target", new_face=False) ), ##### Glance At Other Faces & Continue With The Last Interaction ##### owyl.sequence( self.print_status(str="----- Continue interaction"), owyl.selector( owyl.sequence( self.is_more_than_one_face_target(), self.dice_roll(event="group_interaction"), self.select_a_glance_target(), self.glance_at(id="current_glance_target") ), owyl.succeed() ), self.interact_with_face_target(id="current_face_target", new_face=False) ) ) ) return tree
def create_main_tree(self): tree = owyl.repeatAlways( owyl.sequence( self.poll_tracking(), self.is_stt_on(), self.poll_gesture(), self.is_stt_done(), owyl.selector(self.run_stt_command(), self.run_stt_chat()))) return owyl.visit(tree, blackboard=self.blackboard)
def testRepeatUntilFail(self): """Can we repeat a behavior until it fails? """ bb = blackboard.Blackboard('test', value="foo") checker = lambda x: x and True or False # must eval to True parallel = owyl.parallel repeat = owyl.repeatUntilFail checkBB = blackboard.checkBB setBB = blackboard.setBB tree = parallel( repeat(checkBB(key='value', check=checker), final_value=True), # That should succeed until this sets the value: owyl.selector(owyl.fail(), owyl.fail(), setBB(key='value', value=None)), policy=owyl.PARALLEL_SUCCESS.REQUIRE_ALL) v = owyl.visit(tree, blackboard=bb) results = [x for x in v] result = results[-1] self.assertEqual(result, True) # Need to reset the blackboard to get the same results. bb = blackboard.Blackboard('test', value="foo") v = owyl.visit(tree, blackboard=bb) results = [x for x in v] result = results[-1] self.assertEqual(result, True)
def testRepeatUntilSucceed(self): """Can we repeat a behavior until it succeeds? """ bb = blackboard.Blackboard('test', ) # 'value' defaults to None. checker = lambda x: x is not None parallel = owyl.parallel repeat = owyl.repeatUntilSucceed checkBB = blackboard.checkBB setBB = blackboard.setBB tree = parallel( repeat(checkBB(key='value', check=checker), final_value=True), # That should fail until this sets the value: owyl.selector(owyl.fail(), owyl.fail(), setBB(key='value', value='foo')), policy=owyl.PARALLEL_SUCCESS.REQUIRE_ALL) v = owyl.visit(tree, blackboard=bb) results = [x for x in v] result = results[-1] self.assertEqual(result, True) # Need to reset the blackboard to get the same results. bb = blackboard.Blackboard('test', ) # 'value' defaults to None. v = owyl.visit(tree, blackboard=bb) results = [x for x in v] result = results[-1] self.assertEqual(result, True)
def create_main_tree(self): ''' creates the main tree for owyl behavior tree Args: self The tree looks like this: root | owyl.repeatAlways | owyl.sequence | -------------------------------------------------------- | | | owyl.selector self.TurnToBall self.WalkToBall() ------------------------- | | self.CheckIfBall() self.walkBackwards Returns: Creates a tree and returns owyl.visit method to visit next nodes in the tree. ''' tree = owyl.repeatAlways( owyl.sequence( owyl.selector(self.CheckIfBall(), self.walkBackwards()), self.TurnToBall(), self.WalkToBall())) return owyl.visit(tree, blackboard=self.blackboard)
def someone_arrived(self) : tree = owyl.sequence( self.is_someone_arrived(), owyl.selector( ##### There previously were no people in the scene ##### owyl.sequence( self.were_no_people_in_the_scene(), self.assign_face_target(variable="current_face_target", value="new_face"), self.record_start_time(variable="interact_with_face_target_since"), self.show_expression(emo_class="new_arrival_emotions", trigger="someone_arrived"), self.interact_with_face_target(id="current_face_target", new_face=True, trigger="someone_arrived") ), ##### Currently interacting with someone ##### owyl.sequence( self.is_interacting_with_someone(), self.dice_roll(event="glance_new_face"), self.glance_at_new_face(trigger="someone_arrived") ), ##### Does Nothing ##### owyl.sequence( self.print_status(str="----- Ignoring the new face!"), self.log(behavior="ignore_face", trigger="someone_arrived"), owyl.succeed() ) ), self.clear_new_face_target() ) return tree
def someone_left(self) : tree = owyl.sequence( self.is_someone_left(), owyl.selector( ##### Was Interacting With That Person ##### owyl.sequence( self.was_interacting_with_that_person(), self.return_to_neutral_position(trigger="someone_left"), self.show_frustrated_expression(trigger="someone_left") ), ##### Is Interacting With Someone Else ##### owyl.sequence( self.is_interacting_with_someone(), self.dice_roll(event="glance_lost_face"), self.glance_at_lost_face(trigger="someone_left") ), ##### Does Nothing ##### owyl.sequence( self.print_status(str="----- Ignoring the lost face!"), self.log(behavior="ignore_face", trigger="someone_left"), owyl.succeed() ) ), self.clear_lost_face_target() ) return tree
def testRepeatUntilSucceed(self): """Can we repeat a behavior until it succeeds? """ bb = blackboard.Blackboard('test', ) # 'value' defaults to None. checker = lambda x: x is not None parallel = owyl.parallel repeat = owyl.repeatUntilSucceed checkBB = blackboard.checkBB setBB = blackboard.setBB tree = parallel(repeat(checkBB(key='value', check=checker), final_value=True), # That should fail until this sets the value: owyl.selector(owyl.fail(), owyl.fail(), setBB(key='value', value='foo')), policy=owyl.PARALLEL_SUCCESS.REQUIRE_ALL) v = owyl.visit(tree, blackboard=bb) results = [x for x in v] result = results[-1] self.assertEqual(result, True) # Need to reset the blackboard to get the same results. bb = blackboard.Blackboard('test', ) # 'value' defaults to None. v = owyl.visit(tree, blackboard=bb) results = [x for x in v] result = results[-1] self.assertEqual(result, True)
def testRepeatUntilFail(self): """Can we repeat a behavior until it fails? """ bb = blackboard.Blackboard('test', value="foo") checker = lambda x: x and True or False # must eval to True parallel = owyl.parallel repeat = owyl.repeatUntilFail checkBB = blackboard.checkBB setBB = blackboard.setBB tree = parallel(repeat(checkBB(key='value', check=checker), final_value=True), # That should succeed until this sets the value: owyl.selector(owyl.fail(), owyl.fail(), setBB(key='value', value=None)), policy=owyl.PARALLEL_SUCCESS.REQUIRE_ALL) v = owyl.visit(tree, blackboard=bb) results = [x for x in v] result = results[-1] self.assertEqual(result, True) # Need to reset the blackboard to get the same results. bb = blackboard.Blackboard('test', value="foo") v = owyl.visit(tree, blackboard=bb) results = [x for x in v] result = results[-1] self.assertEqual(result, True)
def nothing_is_happening(self) : tree = owyl.sequence( owyl.selector( ##### Is Not Sleeping ##### owyl.sequence( self.is_not_sleeping(), owyl.selector( ##### Go To Sleep ##### owyl.sequence( self.dice_roll(event="go_to_sleep"), self.record_start_time(variable="sleep_since"), self.print_status(str="----- Go to sleep!"), self.go_to_sleep(trigger="nothing_is_happening") ), ##### Search For Attention ##### self.search_for_attention(trigger="nothing_is_happening") ) ), ##### Is Sleeping ##### owyl.selector( ##### Wake Up ##### owyl.sequence( self.dice_roll(event="wake_up"), self.is_time_to_wake_up(), self.wake_up(trigger="time_to_wake_up"), ), ##### Continue To Sleep ##### owyl.sequence( self.print_status(str="----- Continue to sleep."), self.go_to_sleep(trigger="nothing_is_happening") ) ) ), ##### If Interruption && Sleeping -> Wake Up ##### owyl.sequence( self.is_interruption(), self.is_sleeping(), self.wake_up(trigger="interruption"), self.print_status(str="----- Interruption: Wake up!"), ) ) return tree
def build_tree(self): eva_behavior_tree = \ owyl.repeatAlways( owyl.selector( owyl.sequence( self.is_behavior_tree_on(), self.sync_variables(), ########## Main Events ########## owyl.selector( self.someone_arrived(), self.someone_left(), self.interact_with_people(), self.nothing_is_happening() ) ), self.idle_spin() ) ) return owyl.visit(eva_behavior_tree, blackboard=self.blackboard)
def create_main_tree(self): tree = owyl.repeatAlways( owyl.sequence( self.poll_tracking(), self.is_stt_on(), self.is_stt_done(), owyl.selector(self.run_stt_command(), self.run_stt_chat()), ) ) return owyl.visit(tree, blackboard=self.blackboard)
def interact_with_people(self) : tree = owyl.sequence( self.is_face_target(), owyl.selector( ##### Start A New Interaction ##### owyl.sequence( owyl.selector( self.is_not_interacting_with_someone(), owyl.sequence( self.is_more_than_one_face_target(), self.is_time_to_change_face_target() ) ), self.select_a_face_target(), self.record_start_time(variable="interact_with_face_target_since"), self.interact_with_face_target(id="current_face_target", new_face=False, trigger="people_in_scene") ), ##### Glance At Other Faces & Continue With The Last Interaction ##### owyl.sequence( self.print_status(str="----- Continue interaction"), owyl.selector( owyl.sequence( self.is_more_than_one_face_target(), self.dice_roll(event="group_interaction"), self.select_a_glance_target(), self.glance_at(id="current_glance_target", trigger="people_in_scene") ), owyl.succeed() ), self.interact_with_face_target(id="current_face_target", new_face=False, trigger="people_in_scene"), owyl.selector( owyl.sequence( self.dice_roll(event="face_study_saccade"), self.face_study_saccade(id="current_face_target", trigger="people_in_scene") ), owyl.succeed() ) ) ) ) return tree
def create_main_tree(self): ''' creates the main tree for owyl behavior tree Args: self The tree looks like this: root | owyl.repeatAlways | owyl.sequence | --------------------------------------------------------------------------------------------------------------------------------------------------------- | | | | | owyl.selector owyl.repeatUntilSucceed self.isCameraTrackDone() owyl.repeatUntilSucceed self.isWalkForward() | | | ------------------------------------------------------------------------- self.cameraTrack() self.isBodyTrack() | | | | | self.checkIfBall() self.search85() self.search60() self.search35() self.turnBody() Returns: Creates a tree and returns owyl.visit method to visit next nodes in the tree. ''' # tree=owyl.repeatAlways(self.cameraTrack()) # For testing only the camera tracker ... see method cameraTrack() for details tree = owyl.repeatAlways( owyl.sequence( owyl.selector( self.checkIfBall(), owyl.selector(self.search85(), self.search60(), self.search35(), self.turnBody())), owyl.repeatUntilSucceed(self.cameraTrack()), self.isCameraTrackDone(), owyl.repeatUntilSucceed(self.isBodyTrack()), self.isWalkForward())) return owyl.visit(tree, blackboard=self.blackboard)
def create_main_tree(self): ''' creates the main tree for owyl behavior tree Args: self The tree looks like this: root | owyl.repeatAlways | owyl.sequence | --------------------------------------------------------------------------------------------------------------------------------------------------------- | | | | | owyl.selector owyl.repeatUntilSucceed self.isCameraTrackDone() owyl.repeatUntilSucceed self.isWalkForward() | | | ------------------------------------------------------------------------- self.cameraTrack() self.isBodyTrack() | | | | | self.checkIfBall() self.search85() self.search60() self.search35() self.turnBody() 60() 35() 10() Returns: Creates a tree and returns owyl.visit method to visit next nodes in the tree. ''' # tree=owyl.repeatAlways(self.cameraTrack()) # For testing only the camera tracker ... see method cameraTrack() for details tree=owyl.repeatAlways( owyl.sequence( owyl.selector(self.checkIfBall(),owyl.selector(self.search85(),self.search60(),self.search35(),self.turnBody())) ,owyl.repeatUntilSucceed(self.cameraTrack()) ,self.isCameraTrackDone() ,owyl.repeatUntilSucceed(self.isBodyTrack()) ,self.isWalkForward() ) ) return owyl.visit(tree,blackboard=self.blackboard)
def testVisitSelectorFailure(self): """Can we visit a failing selector? """ tree = owyl.selector(owyl.fail(), owyl.fail(), owyl.fail()) v = owyl.visit(tree) results = [x for x in v if x is not None] self.assertEqual(results, [False, False, False, False]) v = owyl.visit(tree) results = [x for x in v if x is not None] self.assertEqual(results, [False, False, False, False])
def testVisitSelectorSuccess(self): """Can we visit a successful selector? """ tree = owyl.selector(owyl.fail(), owyl.fail(), owyl.succeed(), owyl.fail()) v = owyl.visit(tree) results = [x for x in v if x is not None] self.assertEqual(results, [False, False, True, True]) v = owyl.visit(tree) results = [x for x in v if x is not None] self.assertEqual(results, [False, False, True, True])
def buildTree(self): """ Build the behavior tree. """ tree = owyl.selector( owyl.sequence(self.is_win_move_available(), self.play_win_move()), owyl.sequence(self.is_block_move_available(), self.play_block_move()), owyl.sequence(self.is_fork_available(), self.play_fork_move()), owyl.sequence(self.is_block_fork_available(), self.play_block_fork_move()), owyl.sequence(self.is_center_available(), self.play_center()), owyl.sequence(self.is_opposite_corner_available(), self.play_opposite_corner_move()), owyl.sequence(self.is_corner_available(), self.play_corner_move()), owyl.sequence(self.is_edge_available(), self.play_edge_move())) return owyl.visit(tree)
def testStructureBig(self): tree = owyl.parallel(owyl.sequence(owyl.repeatAlways(blackboard.setBB()), owyl.log()), owyl.selector(owyl.repeatUntilSucceed(blackboard.checkBB())), owyl.repeatUntilFail(owyl.fail())) viztree = OwylTree(tree) structure = truncate(viztree.get_structure(), ['name', 'children']) self.assertEquals(structure, {'name': 'parallel', 'children': [{'name': 'sequence', 'children': [{'name': 'repeatAlways', 'children': [{'name': 'setBB', 'children': []}]}, {'name': 'log', 'children': []}]}, {'name': 'selector', 'children': [{'name': 'repeatUntilSucceed', 'children': [{'name': 'checkBB', 'children': []}]}]}, {'name': 'repeatUntilFail', 'children': [{'name': 'fail', 'children': []}]}]})
def __init__(self, tree_name): self.schedule(self.update) # self.BehaviorNode = rospy.init_node("behavior_tree") rospy.Subscriber("itf_listen", String, self.audioInputCallback) rospy.Subscriber("speech_active", Bool, self.isSpeakingCallback) rospy.Subscriber("facedetect", targets, self.faceDetectCallback) rospy.Subscriber("nmpt_saliency_point", targets, self.saliencyCallback) self.zenodial_listen_pub = rospy.Publisher("zenodial_listen", String, queue_size=1) self.robot_movement_pub = rospy.Publisher("robot_movement", String, queue_size=1) self.commandKeywords = { 'Stop': ['stop', 'halt', 'abort', 'kill', 'panic', 'off', 'freeze', 'shut down', 'turn off', 'help', 'help me', 'abhor', 'a w***e', 'a bore'], 'Walk Forward': ['forward', 'ahead', 'straight', 'forwards'], 'Walk Backward': ['back', 'backward', 'back up', 'backwards'], 'Turn Left': ['turn left', 'turn lefts', 'turns left'], 'Turn Right': ['turn right', 'turn rights', 'turns right']} ### Inputs self.saliencyTargetPos = [0.0, 0.0] # position of the current saliency target self.saliencyTargetVel = 0.0 # average velocity of the current saliency target over the last second self.saliencyTargetAge = 0 # time since the last significant change in the saliency target position self.faceTargetPos = [[0.0, 0.0]] # position of the current face target self.faceTargetVel = 0.0 # average velocity of the current face target over the last second self.faceTargetAge = 0 # time since the last significant change in the face target position self.bodyTargetPos = [[0.0, 0.0]] # position of the current body target self.bodyTargetVel = 0.0 # average velocity of the current body target over the last second self.bodyTargetAge = 0 # time since the last significant change in the body target position self.audioInput = "" # string output of speech-to-text algorithm, raw form self.audioInputAge = 0 # time since the last significant parse of the audio input self.audioInputVol = 0 # average volume or magnitude of the last audio input self.rosInput = "" # string representation of miscellaneous commands from other ros components, usually blender self.rosInputAge = 0 # time since the last ros command self.emotionInput = "" # string output of the audio-emotion-analysis algorithm self.emotionInputAge = 0 # time since the last significant chance in emotional state self.speechOutput = "" # string representation of the last speech output from the robot self.speechOutputAge = 0 # time since the last speech output from the robot self.animationOutput = "" # string representation of the last animation output from the robot self.animationOutputAge = "" # time since the last animation output from the robot self.animationOutputDur = 0 # for zeno body paint self.randomInput = 0 # a random percentile for random behaviors ### Globals self.blinkChance = 0.011 # @ 60 fps a 1.1% chance to start a blink each frame should give us a nice frequency self.highBodyVel = 1 # Not sure what would be considered a high velocity for the body - use 1 for now self.eyeFreedom = 0 self.neckFreedom = 0 self.HEAD_NECK = "headneck" self.UPPER_BODY = "ubody" self.LOWER_BODY = "lbody" ### Locals self.commandName = "" self.actionName = "" self.bodyOrFace = "" self.targetPos = [[0.0, 0.0]] self.glanceOrSaccadeTargetPos = [[0.0, 0.0]] self.firstGreeting = False self.speechActive = False self.idleSince = 0 self.blackboard = blackboard.Blackboard() ### Subtrees ## Blink Subtree. A small example of a tree to run in parallel with the other subtrees. # Assumes randomInput is recalculated each frame self.blinkSubtree = \ owyl.limit( owyl.repeatAlways( owyl.selector( owyl.sequence( self.isSwitchingTarget(), # blink 50% more often when switching targets self.isLess(num1=self.randomInput, num2=self.blinkChance*1.5), self.blink() ), owyl.sequence( owyl.selector( self.isGreater(num1=linalg.norm(self.bodyTargetVel), num2=1), self.isSpeaking() ), self.isLess(num1=self.randomInput, num2=self.blinkChance*1.2), self.blink() ), owyl.sequence( self.isLess(num1=self.randomInput, num2=self.blinkChance), self.blink() ) ) ), limit_period=0.4 # Yield to the other behaviors after every 400 milliseconds of processing ) ## Announce the action we're about to take and then reset the robot to a default stance. # Though we announce an action, this tree doesn't execute the action. # Assumes actionName has been set self.announceAndResetTree = \ owyl.sequence( # announce the action and then reset owyl.selector( # If we're not speaking, then speak self.isSpeaking(), self.sayStartAction(commandName=self.actionToPhrase(self.actionName)) ), owyl.selector( # If we're no in a default stance, reset (blend) to the default stance self.isDefaultStance(), self.resetToDefaultStance() ) ) ## Executes a basic command, such as to play an animation. # Assumes commandName has been set # Assumes bodyOrFace has been set # Will announce the command (if not already speaking) # before showing the associated animation self.executeBasicCommandSubtree = \ owyl.sequence( self.isCommand(commandName=self.commandName), self.setVariable(var=self.actionName, value=self.commandName), owyl.selector( # try the command sequence (subtree) or report failure owyl.sequence( owyl.visit(self.announceAndResetTree, blackboard=self.blackboard), self.showCommand(commandName=self.commandName, part=self.bodyOrFace), # Finally play the command's animation ), owyl.sequence( self.say(utterance="I'm sorry, Dave, I'm afraid I can't do that..."), owyl.fail() ) ) ) ## Select a basic command to execute, once we know that we've been given a command. # Assumes bodyOrFace has been set, to distinguish body actions from face actions self.selectBasicCommandSubtree = \ owyl.selector( # Select from one of several mutually exclusive behaviors owyl.sequence( # If we should be idling, then try to play the Idle animation... self.setVariable(var=self.commandName, value="Idle"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( self.setVariable(var=self.commandName, value="StopSpeech"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( # If we're commanded to and can walk to target location, then play the walk animation until we reach the target self.setVariable(var=self.commandName, value="WalkForward"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( self.setVariable(var=self.commandName, value="WalkBackward"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( self.setVariable(var=self.commandName, value="TurnLeft"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( self.setVariable(var=self.commandName, value="TurnRight"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( self.setVariable(var=self.commandName, value="PointUp"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( self.setVariable(var=self.commandName, value="PointDown"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( self.setVariable(var=self.commandName, value="LookUp"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( self.setVariable(var=self.commandName, value="LookDown"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( self.setVariable(var=self.commandName, value="Wave"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( # If we should show an emotion, then select the right one and show it. self.setVariable(var=self.commandName, value="Smile"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( self.setVariable(var=self.commandName, value="Frown"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( self.setVariable(var=self.commandName, value="FrownMouth"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( self.setVariable(var=self.commandName, value="OpenMouth"), owyl.visit(self.executeBasicCommandSubtree, blackboard=self.blackboard) ) ) ## Tracks the target face or salient point # Assumes targetPos has been set to face, body, or salient position self.faceGaze = \ owyl.sequence( # TODO: Get clarification from Hanson and others on the conditions for tracking # owyl.selector( # self.isFaceNearestAudioSource(self.faceTargetPos), # Do we have the source of the audio? # self.isFaceMostSalient(self.faceTargetAge, self.saliencyTargetAge), # Do we know the degree/magnitude of saliency? # self.isFaceCentered(self.faceTargetPos), # Can we find the centroid of all the faces? # self.isLess(self.randomInput, self.blinkChance*2.0) # Should we really switch tracking targets this often? # ), # self.faceTrack(pos=targetPos, eyeFree=eyeFreedom, neckFree=neckFreedom, rand=-1) # -1 here indicating that we'll track this point until told to stop ) ## Displays the surprised emotional expression under certain conditions # Assumes targetPos has been set to face, body, or salient position self.startle = \ owyl.sequence( owyl.selector( self.isGreater(num1=self.audioInputVol, num2=1), # or whatever counts for a high volume self.isGreater(num1=linalg.norm(self.faceTargetVel), num2=1), self.isGreater(num1=linalg.norm(self.bodyTargetVel), num2=1), self.isGreater(num1=linalg.norm(self.saliencyTargetVel), num2=1) ), self.showAction(action="OpenMouth", part=self.HEAD_NECK) # self.showAction(action="Surprised", part="face") ) ## Random eye movements which are much faster and less pronounced than glances. # Assumes targetPos has been set to face or salient position # Assumes glanceOrSaccadeTargetPos has been set to face's body or salient point nearby # Assumes eyeFreedom and neckFreedom have been set to appropriate degrees of freedom self.saccade = \ owyl.selector( owyl.sequence( self.isGreater(num1=self.randomInput, num2=0.5), self.faceTrack(pos=self.glanceOrSaccadeTargetPos, eyeFree=self.randomInput*0.25*self.eyeFreedom, neckFree=self.randomInput*0.10*self.neckFreedom, rand=self.randomInput) ), owyl.sequence( self.faceTrack(pos=self.glanceOrSaccadeTargetPos, eyeFree=self.randomInput*0.75*self.eyeFreedom, neckFree=self.randomInput*0.30*self.neckFreedom, rand=self.randomInput) ) ) ## Random eye movements which signal recognition of targets. # Assumes targetPos has been set to face or salient position # Assumes glanceOrSaccadeTargetPos has been set to face's body or salient point nearby self.glance = \ owyl.selector( owyl.sequence( owyl.selector( self.isLess(num1=self.faceTargetAge, num2=1), self.isLess(num1=self.randomInput, num2=0.0025) ), self.faceTrack(pos=self.glanceOrSaccadeTargetPos, eyeFree=self.eyeFreedom, neckFree=self.neckFreedom, rand=self.randomInput*2.5) ), owyl.sequence( owyl.selector( self.isLess(num1=self.saliencyTargetAge, num2=1), self.isLess(num1=self.randomInput, num2=0.0025) ), self.faceTrack(pos=self.glanceOrSaccadeTargetPos, eyeFree=self.eyeFreedom, neckFree=self.neckFreedom, rand=self.randomInput*2.5) ) ) ## After tracking at a new target face, ZoidStein will execute a scripted greeting. # Be careful not to play this more than once in the same encounter. self.greeting = \ owyl.sequence( self.isVariable(var=self.firstGreeting, value=False), self.setVariable(var=self.firstGreeting, value=True), self.say(utterance="Hello!"), self.showAction(action="Wave", part=self.UPPER_BODY), self.showAction(action="Smile", part=self.HEAD_NECK) ) ## When people are too close, move head back and up while playing the afraid expression animation. self.awkward = \ owyl.sequence( self.showAction(action="LookUp", part=self.HEAD_NECK), # self.showAction(action="Afraid", part="face") self.showAction(action="Frown", part=self.HEAD_NECK) ) ## When people are very close, move head forward and down while playing the innoscent expression animation. self.shy = \ owyl.sequence( self.showAction(action="LookDown", part=self.HEAD_NECK), # self.showAction(action="Innocent", part=self.HEAD_NECK) self.showAction(action="Frown", part=self.HEAD_NECK) ) ## In general, ZoidStein's expressions should mimic the emotional input of its targets. self.mimic = \ owyl.selector( owyl.sequence( self.isVariable(var=self.emotionInput, value="Happy"), self.showAction(action="Happy", part=self.UPPER_BODY), self.showAction(action="Happy", part=self.HEAD_NECK) ) # TODO: Do we have to mimic all the emotionInput or just happy? ) """ Creating the tree """ for case in switch(tree_name): if case("BasicZenoTree"): # self.robot = Zeno() self.makeBasicZenoTree() break if case("BasicZoidSteinTree"): self.robot = Zoidstein() self.makeBasicZoidSteinTree() break if case(): rospy.loginfo("Unrecognized Tree Name!\n")
def makeBasicTree(self): robotTree = \ owyl.parallel( ######################################## BodySubtree ######################################## owyl.limit( owyl.repeatAlways( owyl.sequence( self.updateFrontVariables(), self.determineCurrentTarget(), self.removeFace(), owyl.selector( # Gaze at face targets owyl.sequence( self.isFaceTarget(), self.isNoSalientTarget(), self.isNoAudioInput(), self.isNoRosInput(), self.isNoEmotionInput(), self.faceGaze() ), # Gaze at salient targets # owyl.sequence( # self.isSalientTarget(), # # self.isNoFaceTarget(), # self.isNoAudioInput(), # self.isNoRosInput(), # self.isNoEmotionInput(), # self.faceGaze() # ), # Handle commands owyl.sequence( owyl.selector( self.isAudioInput(), self.isRosInput() ), owyl.selector( self.isCommand(key="audioInput"), self.isCommand(key="rosInput") ), owyl.selector( owyl.sequence( owyl.selector( self.isCommandPhrase(commandName="StopSpeech", actionPhrase="actionName"), self.isCommandPhrase(commandName="WalkForward", actionPhrase="actionName"), self.isCommandPhrase(commandName="WalkBackward", actionPhrase="actionName"), self.isCommandPhrase(commandName="TurnLeft", actionPhrase="actionName"), self.isCommandPhrase(commandName="TurnRight", actionPhrase="actionName"), self.isCommandPhrase(commandName="StopSpeaking", actionPhrase="actionName"), self.isCommandPhrase(commandName="Smile", actionPhrase="actionName"), self.isCommandPhrase(commandName="Frown", actionPhrase="actionName"), # self.isCommandPhrase(commandName="FrownMouth", actionPhrase="actionName"), self.isCommandPhrase(commandName="Surprise", actionPhrase="actionName"), self.isCommandPhrase(commandName="TakeThis", actionPhrase="actionName"), self.isCommandPhrase(commandName="GiveBack", actionPhrase="actionName"), self.isCommandPhrase(commandName="Wave", actionPhrase="actionName"), ), self.isNotSpeaking(), # self.sayStartAction(key="actionName"), self.showAction(key="actionName") ), self.printStatus(msg="I'm sorry, Dave, I'm afraid I can't do that...") ) ), # Play emotion detection game owyl.sequence( owyl.selector( #TODO: change to sequence self.isAudioInput(), self.isEmotionInput(), ), self.isNotStopEmotionDetection(key="audioInput"), self.isEmotionDetection(key="audioInput"), self.isNotSpeaking(), self.startEmotionDetection(), ), # Play object recognition game owyl.sequence( owyl.selector( self.isAudioInput(), self.isObjInput(), ), self.isNotStopObjRecognition(key="audioInput"), self.isObjRecognition(key="audioInput"), self.isNotSpeaking(), self.startObjRecognition() ), # Send to the dialogue system owyl.sequence( self.isAudioInput(), self.isNotSpeaking(), self.toZenoDial(key="audioInput") ) ) ) ), limit_period=0.001 ), ######################################## General tree ######################################## owyl.limit( owyl.repeatAlways( owyl.sequence( self.test(), self.updateVariables() ) ), limit_period=0.001 ), policy=owyl.PARALLEL_SUCCESS.REQUIRE_ALL ) return owyl.visit(robotTree, blackboard=self.blackboard)
def makeBasicZoidSteinTree(self): ## The scripted dance of ZoidStein, used when no faces or salient targets are detected. # Assumes body state has been reset to starting state zoidSteinBodyDance = \ owyl.sequence( self.showCommand(commandName="WalkForward", part=self.LOWER_BODY), self.showCommand(commandName="WalkBackward", part=self.LOWER_BODY), self.showAction(commandName="PointUp", part=self.UPPER_BODY), self.showAction(commandName="PointDown", part=self.UPPER_BODY) ) ## body behavior subtree # TODO: Attach subtrees properly zoidSteinBodySubtree = \ owyl.limit( owyl.repeatAlways( owyl.selector( # Select response to command or natural behavior owyl.sequence( # If the last audio or blender input is a command, then select a response self.isCommand(commandName=self.commandName), self.setVariable(var=self.bodyOrFace, value="body"), owyl.visit(self.selectBasicCommandSubtree, blackboard=self.blackboard) ), # It's not a command, so start checking for natural behaviors owyl.sequence( # self.isNoSalientTarget(), # self.isNoFaceTarget(), # self.isNoAudioInput(), # self.isNoRosInput(), # self.isNoEmotionInput(), self.isIdle(), # There's nothing to do, so let's dance! owyl.visit(zoidSteinBodyDance, blackboard=self.blackboard) ), owyl.sequence( #TODO: the other natural actions, once we have a saliency target, etc. ) ) ), limit_period=0.4 # Yield to the other behaviors after every 400 milliseconds of processing ) ## face & neck behavior subtree # TODO: Attach subtrees properly zoidSteinFaceSubtree = \ owyl.limit( owyl.repeatAlways( owyl.selector( # Select from one of several mutually exclusive face & neck behaviors owyl.sequence( # If the last audio or blender input is a command, then select a response self.isCommand(commandName=self.commandName), self.setVariable(var=self.bodyOrFace, value=self.HEAD_NECK), owyl.visit(self.selectBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( # self.isSalientTarget(), # self.isNoFaceTarget(), # self.isNoAudioInput(), # self.isNoRosInput(), # self.isNoEmotionInput(), self.isIdle(), owyl.visit(self.faceGaze, blackboard=self.blackboard) ), owyl.sequence( self.isFaceTarget(), ) ) ), limit_period=0.4 # Yield to the other behaviors after every 400 milliseconds of processing ) ## ZoidStein's root tree zoidSteinTree = \ owyl.parallel( # At the highest level, run several parallel behaviors owyl.visit(zoidSteinBodySubtree, blackboard=self.blackboard), owyl.visit(zoidSteinFaceSubtree, blackboard=self.blackboard), owyl.limit( owyl.repeatAlways( owyl.sequence( # Poll for input coming from blender, for example buttons to stop movement, etc. # May move this logic out of the behavior tree... # self.pollForBlenderInput(), # Listen for audio input from people talking, etc. # Again, this might not be the best place for this... # self.listenForAudioInput() ) ), limit_period=0.4 # Yield to the other behaviors after every 400 milliseconds of processing ), policy=owyl.PARALLEL_SUCCESS.REQUIRE_ALL ) return owyl.visit(zoidSteinTree, blackboard=self.blackboard)
def build_tree(self): eva_behavior_tree = \ owyl.repeatAlways( owyl.selector( owyl.sequence( self.is_scripted_performance_system_off(), self.sync_variables(), ########## Main Events ########## owyl.selector( ##### When Someone Arrived ##### owyl.sequence( self.is_someone_arrived(), self.set_emotion(variable="boredom_engagement", value=0.5), owyl.selector( ##### Were No People In The Scene ##### owyl.sequence( self.were_no_people_in_the_scene(), self.update_emotion(variable="sadness_happiness", lower_limit=0.0, min=1.2, max=1.4), self.update_emotion(variable="boredom_engagement", lower_limit=0.0, min=1.2, max=1.4), self.assign_face_target(variable="current_face_target", value="new_face"), self.record_start_time(variable="interact_with_face_target_since"), self.interact_with_face_target(id="current_face_target", new_face=True) ), ##### Is Interacting With Someone ##### owyl.sequence( self.is_interacting_with_someone(), self.is_random_smaller_than(val1="newRandom", val2="glance_probability_for_new_faces"), self.update_emotion(variable="sadness_happiness", lower_limit=0.0, min=1.05, max=1.1), self.update_emotion(variable="boredom_engagement", lower_limit=0.0, min=1.05, max=1.1), self.glance_at_new_face() ), ##### Does Nothing ##### owyl.sequence( self.print_status(str="----- Ignoring The New Face!"), self.does_nothing() ) ), self.clear_new_face_target() ), ##### When Someone Left ##### owyl.sequence( self.is_someone_left(), owyl.selector( ##### Was Interacting With That Person ##### owyl.sequence( self.was_interacting_with_that_person(), self.update_emotion(variable="confusion_comprehension", lower_limit=0.0, min=0.4, max=0.6), self.update_emotion(variable="recoil_surprise", lower_limit=0.0, min=1.8, max=2.2), self.update_emotion(variable="sadness_happiness", lower_limit=0.0, min=0.4, max=0.6), self.update_emotion(variable="irritation_amusement", lower_limit=0.0, min=0.95, max=1.0), self.show_frustrated_expression() ), ##### Is Interacting With Someone Else ##### owyl.sequence( self.is_interacting_with_someone(), self.is_random_smaller_than(val1="newRandom", val2="glance_probability_for_lost_faces"), self.glance_at_lost_face() ), ##### Does Nothing ##### owyl.sequence( self.print_status(str="----- Ignoring The Lost Face!"), self.does_nothing() ) ), self.clear_lost_face_target() ), ##### People Interaction ##### owyl.sequence( self.is_face_target(), self.update_emotion(variable="sadness_happiness", lower_limit=0.0, min=1.001, max=1.005), self.update_emotion(variable="boredom_engagement", lower_limit=0.0, min=1.005, max=1.01), owyl.selector( ##### Start A New Interaction ##### owyl.sequence( owyl.selector( self.is_not_interacting_with_someone(), owyl.sequence( self.is_more_than_one_face_target(), self.is_time_to_change_face_target() ) ), self.select_a_face_target(), self.record_start_time(variable="interact_with_face_target_since"), self.interact_with_face_target(id="current_face_target", new_face=False) ), ##### Glance At Other Faces & Continue With The Last Interaction ##### owyl.sequence( self.print_status(str="----- Continue The Interaction"), owyl.selector( owyl.sequence( self.is_more_than_one_face_target(), self.is_random_smaller_than(val1="newRandom", val2="glance_probability"), self.select_a_glance_target(), self.glance_at(id="current_glance_target") ), self.does_nothing() ), self.interact_with_face_target(id="current_face_target", new_face=False) ) ) ), ##### Nothing Interesting Is Happening ##### owyl.sequence( self.update_emotion(variable="boredom_engagement", lower_limit=0.0, min=0.8, max=0.9), self.update_emotion(variable="sadness_happiness", lower_limit=0.0, min=0.995, max=1.0), owyl.selector( ##### Is Not Sleeping ##### owyl.sequence( self.is_not_sleeping(), owyl.selector( ##### Go To Sleep ##### owyl.sequence( self.is_random_smaller_than(val1="newRandom_plus_boredom", val2="sleep_probability"), self.record_start_time(variable="sleep_since"), self.print_status(str="----- Go To Sleep!"), self.go_to_sleep() ), ##### Search For Attention ##### self.search_for_attention() ) ), ##### Is Sleeping ##### owyl.selector( ##### Wake Up ##### owyl.sequence( self.is_random_smaller_than(val1="newRandom", val2="wake_up_probability"), self.is_time_to_wake_up(), self.wake_up(), self.update_emotion(variable="boredom_engagement", lower_limit=0.3, min=1.5, max=2.0) ), ##### Continue To Sleep ##### owyl.sequence( self.print_status(str="----- Continue To Sleep!"), self.go_to_sleep() ) ) ), ##### If Interruption && Sleeping -> Wake Up ##### owyl.sequence( self.is_interruption(), self.is_sleeping(), self.wake_up(), self.print_status(str="----- Interruption: Wake Up!"), self.update_emotion(variable="boredom_engagement", lower_limit=0.3, min=1.5, max=2.0) ) ) ) ), ############### Scripted Performance System ############### owyl.sequence( self.is_scripted_performance_system_on(), self.start_scripted_performance_system() ) ) ) return owyl.visit(eva_behavior_tree, blackboard=self.blackboard)
def makeBasicZenoTree(self): ## Zeno's Body Paint subtree zenoBodyPaint = \ owyl.selector( owyl.sequence( self.isNotSameBrushStroke(), self.isGreater(num1=self.animationOutputDur, num2=2), self.setVariable(var=self.actionName, value="BrushStrokeGesture"), owyl.selector( # try the action sequence (subtree) or report failure owyl.sequence( owyl.visit(self.announceAndResetTree, blackboard=self.blackboard), self.showAction(action=self.actionName, part=self.HEAD_NECK) # Finally play the action's animation ), owyl.sequence( self.say(utterance="I'm not feeling inspired today..."), owyl.fail() ) ) ), owyl.sequence( self.setVariable(var=self.actionName, value="Idle"), owyl.selector( # try the command sequence (subtree) or report failure owyl.sequence( owyl.visit(self.announceAndResetTree, blackboard=self.blackboard), self.showAction(action=self.actionName, part=self.HEAD_NECK) # Finally play the action's animation ), owyl.sequence( self.say(utterance="Why can't I stand?"), owyl.fail() ) ) ) ) ## body behavior subtree zenoBodySubtree = \ owyl.limit( owyl.repeatAlways( owyl.selector( # Select response to command or natural behavior owyl.sequence( # If the last audio or blender input is a command, then select a response self.isCommand(commandName=self.commandName), self.setVariable(var=self.bodyOrFace, value=self.UPPER_BODY), owyl.visit(self.selectBasicCommandSubtree, blackboard=self.blackboard) ), # It's not a command, so start checking for natural behaviors owyl.sequence( # self.isNoSalientTarget(), # self.isNoFaceTarget(), # self.isNoAudioInput(), # self.isNoRosInput(), # self.isNoEmotionInput(), self.isIdle(), # There's nothing to do, so let's paint! owyl.visit(zenoBodyPaint, blackboard=self.blackboard) ), owyl.sequence( # TODO: the other natural actions, once we have a saliency target, etc. ) ) ), limit_period=0.4 # Yield to the other behaviors after every 400 milliseconds of processing ) # face & neck behavior subtree zenoFaceSubtree = \ owyl.limit( owyl.repeatAlways( owyl.selector( # Select from one of several mutually exclusive face & neck behaviors owyl.sequence( # If the last audio or blender input is a command, then select a response self.isCommand(commandName=self.commandName), self.setVariable(var=self.bodyOrFace, value=self.HEAD_NECK), owyl.visit(self.selectBasicCommandSubtree, blackboard=self.blackboard) ), owyl.sequence( # self.isSalientTarget(), # self.isNoFaceTarget(), # self.isNoAudioInput(), # self.isNoRosInput(), # self.isNoEmotionInput(), self.isIdle(), owyl.visit(self.faceGaze, blackboard=self.blackboard) ), owyl.sequence( self.isFaceTarget() ) ) ), limit_period=0.4 # Yield to the other behaviors after every 400 milliseconds of processing ) # Zeno's root tree zenoTree = \ owyl.parallel( # At the highest level, run several parallel behaviors owyl.visit(zenoBodySubtree, blackboard=self.blackboard), owyl.visit(zenoFaceSubtree, blackboard=self.blackboard), owyl.limit( owyl.repeatAlways( owyl.sequence( # Poll for input coming from blender, for example buttons to stop movement, etc. # May move this logic out of the behavior tree... # self.pollForBlenderInput(), # Listen for audio input from people talking, etc. # Again, this might not be the best place for this... # self.listenForAudioInput() ) ), limit_period=0.4 # Yield to the other behaviors after every 400 milliseconds of processing ), policy=owyl.PARALLEL_SUCCESS.REQUIRE_ALL ) return owyl.visit(zenoTree, blackboard=self.blackboard)