39 import roslib; roslib.load_manifest(
'velma_task_cs_ros_interface')
44 from velma_common
import *
45 from rcprg_ros_utils
import exitError
47 if __name__ ==
"__main__":
49 rospy.init_node(
'head_test', anonymous=
True)
53 print "This test/tutorial executes complex motions"\
54 " of head along with motions in Joint Impedance mode." 56 print "Running python interface for Velma..." 57 velma = VelmaInterface()
58 print "Waiting for VelmaInterface initialization..." 59 if not velma.waitForInit(timeout_s=10.0):
60 print "Could not initialize VelmaInterface\n" 62 print "Initialization ok!\n" 64 diag = velma.getCoreCsDiag()
65 if not diag.motorsReady():
66 print "Motors must be homed and ready to use for this test." 69 print "Motors must be enabled every time after the robot enters safe state." 70 print "If the motors are already enabled, enabling them has no effect." 71 print "Enabling motors..." 72 if velma.enableMotors() != 0:
75 print "Moving to the current position..." 76 velma.moveJointImpToCurrentPos(start_time=0.5)
77 error = velma.waitForJoint()
79 print "The action should have ended without error, but the error code is", error
82 print "moving head to position: left" 84 velma.moveHead(q_dest, 2.0, start_time=0.5)
85 if velma.waitForHead() != 0:
90 print "moving head to position: right (interrupted by invalid motion in Joint Impedance mode)" 92 velma.moveHead(q_dest, 10.0, start_time=0.5)
96 print "Moving too fast to another position (safe mode in velma_core_ve_body)..." 97 q_map_0 = {
'torso_0_joint':0,
98 'right_arm_0_joint':0,
99 'right_arm_1_joint':0,
100 'right_arm_2_joint':0,
101 'right_arm_3_joint':0,
102 'right_arm_4_joint':0,
103 'right_arm_5_joint':0,
104 'right_arm_6_joint':0,
105 'left_arm_0_joint':0,
106 'left_arm_1_joint':0,
107 'left_arm_2_joint':0,
108 'left_arm_3_joint':0,
109 'left_arm_4_joint':0,
110 'left_arm_5_joint':0,
111 'left_arm_6_joint':0}
113 velma.moveJoint(q_map_0, 0.05, start_time=0.5, position_tol=0, velocity_tol=0)
114 error = velma.waitForJoint()
116 print "The action should have ended with error, but the error code is", error
119 if velma.waitForHead() == 0:
128 print "Motors must be enabled every time after the robot enters safe state." 129 print "If the motors are already enabled, enabling them has no effect." 130 print "Enabling motors..." 131 if velma.enableMotors() != 0:
134 print "Moving to the current position..." 135 js = velma.getLastJointState()
136 velma.moveJoint(js[1], 0.5, start_time=0.5, position_tol=15.0/180.0*math.pi)
137 error = velma.waitForJoint()
139 print "The action should have ended without error, but the error code is", error
142 print "Checking if old trajectory for head is continued..." 147 print "moving head to position: 0" 149 velma.moveHead(q_dest, 2.0, start_time=0.5)
150 if velma.waitForHead() != 0:
def isHeadConfigurationClose(q1, q2, tolerance=0.1)
Check if two configurations of robot neck are close within tolerance.