camera_walk_pose.py
Go to the documentation of this file.
00001 import rospy
00002 
00003 # go to crouching position
00004 def cameraWalkPose(motionProxy,head_pitch,head_yaw):
00005         numJoints = len(motionProxy.getJointNames('Body'))
00006         
00007         allAngles = [head_yaw,head_pitch,                                       # head
00008                 1.39, 0.34, -1.39, -1.04, 0.0, 0.0,             # left arm
00009                 0.0, 0.0, -0.43, 0.69, -0.34, 0.0,      # left leg
00010                 0.0, 0.0, -0.43, 0.69, -0.34, 0.0,      # right leg
00011                 1.39, -0.34, 1.39, 1.04, 0.0, 0.0]              # right arm
00012         
00013 
00014         if (numJoints == 26):
00015                 angles = allAngles
00016         elif (numJoints == 22):  # no hands (e.g. simulator)
00017                 angles = allAngles[0:6] + allAngles[8:24]
00018         else:
00019            rospy.logerr("Unkown number of joints: %d", numJoints)
00020            return 
00021                 
00022         try:
00023                 motionProxy.angleInterpolation('Body', angles, 1.5, True);
00024 
00025         except RuntimeError,e:
00026                 print "An error has been caught"
00027                 print e
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


nao_driver
Author(s): Armin Hornung, Stefan Osswald, Daniel Maier
autogenerated on Tue Oct 15 2013 10:06:23