Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 import threading
00036 import rospy
00037 import actionlib
00038
00039 from nao_driver import NaoNode
00040
00041 from nao_msgs.msg import RunBehaviorAction
00042
00043 from nao_msgs.srv import (
00044 GetInstalledBehaviors,
00045 GetInstalledBehaviorsResponse,
00046 )
00047
00048 class NaoBehaviors(NaoNode):
00049
00050 NODE_NAME = "nao_behaviors"
00051
00052 def __init__( self ):
00053
00054
00055 NaoNode.__init__( self, self.NODE_NAME )
00056
00057
00058 self.behavior = None
00059 self.lock = threading.RLock()
00060
00061
00062 self.behaviorProxy = self.get_proxy( "ALBehaviorManager" )
00063
00064
00065 self.getInstalledBehaviorsService = rospy.Service(
00066 "get_installed_behaviors",
00067 GetInstalledBehaviors,
00068 self.getInstalledBehaviors
00069 )
00070
00071
00072 self.actionlibServer = actionlib.SimpleActionServer(
00073 "run_behavior",
00074 RunBehaviorAction,
00075 self.runBehavior,
00076 False
00077 )
00078
00079 self.actionlibServer.register_preempt_callback( self.stopBehavior )
00080
00081 self.actionlibServer.start()
00082
00083 def getInstalledBehaviors( self, request ):
00084 result = self.behaviorProxy.getInstalledBehaviors()
00085 return GetInstalledBehaviorsResponse( result )
00086
00087
00088 def runBehavior( self, request ):
00089
00090 rospy.logdebug(
00091 "Execution of behavior: '{}' requested".format(request.behavior))
00092
00093
00094 if not request.behavior in self.behaviorProxy.getInstalledBehaviors():
00095 error_msg = "Behavior '{}' not installed".format(request.behavior)
00096 self.actionlibServer.set_aborted(text = error_msg)
00097 rospy.logdebug(error_msg)
00098 return
00099
00100 with self.lock:
00101
00102 if self.actionlibServer.is_preempt_requested():
00103 self.actionlibServer.set_preempted()
00104 rospy.logdebug("Behavior execution preempted before it started")
00105 return
00106
00107
00108 self.behavior = request.behavior
00109
00110 taskID = self.behaviorProxy.post.runBehavior( self.behavior )
00111
00112
00113 rospy.logdebug("Waiting for behavior execution to complete")
00114 self.behaviorProxy.wait( taskID, 0 )
00115
00116
00117 with self.lock:
00118 self.behavior = None
00119
00120 if self.actionlibServer.is_preempt_requested() :
00121 self.actionlibServer.set_preempted()
00122 rospy.logdebug("Behavior execution preempted")
00123
00124 else:
00125 self.actionlibServer.set_succeeded()
00126 rospy.logdebug("Behavior execution succeeded")
00127
00128 def stopBehavior( self ):
00129 with self.lock:
00130 if self.behavior and self.actionlibServer.is_active() :
00131 self.behaviorProxy.stopBehavior( self.behavior )
00132
00133
00134 if __name__ == '__main__':
00135 node = NaoBehaviors()
00136 rospy.loginfo( node.NODE_NAME + " running..." )
00137 rospy.spin()
00138 rospy.loginfo( node.NODE_NAME + " stopped." )
00139 exit(0)
nao_driver
Author(s): Armin Hornung, Armin Hornung, Stefan Osswald, Daniel Maier, Miguel Sarabia, Séverin Lemaignan
autogenerated on Thu Oct 30 2014 09:20:04