Go to the documentation of this file.00001 import rospy
00002
00003
00004 def cameraWalkPose(motionProxy,head_pitch,head_yaw):
00005 numJoints = len(motionProxy.getJointNames('Body'))
00006
00007 allAngles = [head_yaw,head_pitch,
00008 1.39, 0.34, -1.39, -1.04, 0.0, 0.0,
00009 0.0, 0.0, -0.43, 0.69, -0.34, 0.0,
00010 0.0, 0.0, -0.43, 0.69, -0.34, 0.0,
00011 1.39, -0.34, 1.39, 1.04, 0.0, 0.0]
00012
00013
00014 if (numJoints == 26):
00015 angles = allAngles
00016 elif (numJoints == 22):
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