def main(): exercices = [1, 2, 4, 5, 6] print '##############################################################' print ' CYBERNETIQUE APPLIQUEE ' print ' PROJET DE SEMESTRE PRINTEMPS 2011 ' print ' PARCOURS VITA POUR NAO ' print ' ----------------------------------------- ' print ' Parcours predefini pour tester l\'enchainement des exercices ' print '##############################################################' print '' print '' # connexion au robot Nao c = connexion() ALMotionProxy = c.getProxy('ALMotion') # objet permettant d'asservir / desasservir les moteurs du robot asservir = Stiffness.Stiffness(ALMotionProxy) asservir.asservir() # objet permettant d'initialiser la position du robo init = Init_Pose.Init_Pose(ALMotionProxy) # objet controlant les deplacements du Nao d'un exercice a l'autre deplacements = Deplacements.Deplacements(c) ####################################################### # Suite d'enchainements du parcours predefini for crtEx in exercices: doEnchainement(init, deplacements, ALMotionProxy, crtEx) ALFrameProxy = c.getProxy("ALFrameManager") ## ## #behaviorID = ALFrameProxy.newBehaviorFromFile("/home/nao/behaviors/standup.xar", "") ## behaviorID = ALFrameProxy.newBehaviorFromFile( "/home/nao/behaviors/behavior.xar", "") ALFrameProxy.completeBehavior(behaviorID) ####################################################### # FIN asservir.desasservir()
def finalise(self): # mets le robot en position Init_Pose initPose = Init_Pose.Init_Pose(self.__proxy) initPose.do()
def finalise(self): self.termineExercice() # mets le robot en position Init_Pose initPose = Init_Pose.Init_Pose(self.__proxy) initPose.do()
def init4ExerciceGauche(self): # mets le robot en position Init_Pose initPose = Init_Pose.Init_Pose(self.__proxy) initPose.do() names = list() times = list() keys = list() names.append("HeadYaw") times.append([ 0.10000]) keys.append([ [ 0.00000, [ 2, -0.03333, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("HeadPitch") times.append([ 0.10000]) keys.append([ [ 0.00000, [ 2, -0.03333, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("LShoulderPitch") times.append([ 0.10000, 1.50000]) keys.append([ [ 1.39626, [ 2, -0.03333, 0.00000], [ 2, 0.46667, 0.00000]], [ 1.39626, [ 2, -0.46667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("LShoulderRoll") times.append([ 0.10000, 1.50000, 3.00000]) keys.append([ [ 0.34907, [ 2, -0.03333, 0.00000], [ 2, 0.46667, 0.00000]], [ 0.87266, [ 2, -0.46667, -0.04887], [ 2, 0.50000, 0.05236]], [ 0.92502, [ 2, -0.50000, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("LElbowYaw") times.append([ 0.10000, 1.50000]) keys.append([ [ -1.39626, [ 2, -0.03333, 0.00000], [ 2, 0.46667, 0.00000]], [ 0.17453, [ 2, -0.46667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("LElbowRoll") times.append([ 0.10000, 1.50000]) keys.append([ [ -1.04720, [ 2, -0.03333, 0.00000], [ 2, 0.46667, 0.00000]], [ -1.56207, [ 2, -0.46667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("LWristYaw") times.append([ 0.10000]) keys.append([ [ 0.00000, [ 2, -0.03333, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("LHand") times.append([ 0.10000]) keys.append([ [ 0.00000, [ 2, -0.03333, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("RShoulderPitch") times.append([ 0.10000, 1.50000]) keys.append([ [ 1.39626, [ 2, -0.03333, 0.00000], [ 2, 0.46667, 0.00000]], [ 1.39626, [ 2, -0.46667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("RShoulderRoll") times.append([ 0.10000, 1.50000, 3.00000]) keys.append([ [ -0.34907, [ 2, -0.03333, 0.00000], [ 2, 0.46667, 0.00000]], [ -0.87266, [ 2, -0.46667, 0.04887], [ 2, 0.50000, -0.05236]], [ -0.92502, [ 2, -0.50000, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("RElbowYaw") times.append([ 0.10000, 1.50000]) keys.append([ [ 1.39626, [ 2, -0.03333, 0.00000], [ 2, 0.46667, 0.00000]], [ -0.17453, [ 2, -0.46667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("RElbowRoll") times.append([ 0.10000, 1.50000]) keys.append([ [ 1.04720, [ 2, -0.03333, 0.00000], [ 2, 0.46667, 0.00000]], [ 1.56207, [ 2, -0.46667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("RWristYaw") times.append([ 0.10000]) keys.append([ [ 0.00000, [ 2, -0.03333, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("RHand") times.append([ 0.10000]) keys.append([ [ 0.00000, [ 2, -0.03333, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("LHipYawPitch") times.append([ 0.10000, 3.00000]) keys.append([ [ 0.00000, [ 2, -0.03333, 0.00000], [ 2, 0.96667, 0.00000]], [ -0.69813, [ 2, -0.96667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("LHipRoll") times.append([ 0.10000, 3.00000]) keys.append([ [ 0.00000, [ 2, -0.03333, 0.00000], [ 2, 0.96667, 0.00000]], [ 0.10472, [ 2, -0.96667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("LHipPitch") times.append([ 0.10000, 3.00000]) keys.append([ [ -0.43633, [ 2, -0.03333, 0.00000], [ 2, 0.96667, 0.00000]], [ -0.40143, [ 2, -0.96667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("LKneePitch") times.append([ 0.10000, 3.00000]) keys.append([ [ 0.69813, [ 2, -0.03333, 0.00000], [ 2, 0.96667, 0.00000]], [ 1.13446, [ 2, -0.96667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("LAnklePitch") times.append([ 0.10000, 3.00000]) keys.append([ [ -0.34907, [ 2, -0.03333, 0.00000], [ 2, 0.96667, 0.00000]], [ -0.29671, [ 2, -0.96667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("LAnkleRoll") times.append([ 0.10000]) keys.append([ [ 0.00000, [ 2, -0.03333, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("RHipRoll") times.append([ 0.10000, 3.00000]) keys.append([ [ 0.00000, [ 2, -0.03333, 0.00000], [ 2, 0.96667, 0.00000]], [ -0.73832, [ 2, -0.96667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("RHipPitch") times.append([ 0.10000, 3.00000]) keys.append([ [ -0.43633, [ 2, -0.03333, 0.00000], [ 2, 0.96667, 0.00000]], [ 0.26180, [ 2, -0.96667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("RKneePitch") times.append([ 0.10000, 3.00000]) keys.append([ [ 0.69813, [ 2, -0.03333, 0.00000], [ 2, 0.96667, 0.00000]], [ -0.08727, [ 2, -0.96667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("RAnklePitch") times.append([ 0.10000, 3.00000]) keys.append([ [ -0.34907, [ 2, -0.03333, 0.00000], [ 2, 0.96667, 0.00000]], [ 0.36652, [ 2, -0.96667, 0.00000], [ 2, 0.00000, 0.00000]]]) names.append("RAnkleRoll") times.append([ 0.10000, 3.00000]) keys.append([ [ 0.00000, [ 2, -0.03333, 0.00000], [ 2, 0.96667, 0.00000]], [ 0.57596, [ 2, -0.96667, 0.00000], [ 2, 0.00000, 0.00000]]]) try: self.__proxy.angleInterpolationBezier(names, times, keys); except BaseException, err: print str(err)