39 import roslib; roslib.load_manifest(
'velma_task_cs_ros_interface')
42 from velma_common
import *
43 from rcprg_ros_utils
import exitError
46 return float(deg)/180.0*math.pi
48 if __name__ ==
"__main__":
50 rospy.init_node(
'grippers_test', anonymous=
False)
52 print "waiting for init..." 54 velma = VelmaInterface()
56 print "Waiting for VelmaInterface initialization..." 57 if not velma.waitForInit(timeout_s=10.0):
58 print "Could not initialize VelmaInterface\n" 61 print "Initialization ok!\n" 63 diag = velma.getCoreCsDiag()
64 if not diag.motorsReady():
65 print "Motors must be homed and ready to use for this test." 68 if velma.enableMotors() != 0:
71 print "Switch to jnt_imp mode (no trajectory)..." 72 velma.moveJointImpToCurrentPos(start_time=0.5)
73 error = velma.waitForJoint()
75 print "The action should have ended without error, but the error code is", error
84 if velma.waitForHandLeft() != 0:
89 exitError(3, msg=
"configuration of hand should be 0")
93 velma.resetHandRight()
94 if velma.waitForHandRight() != 0:
99 exitError(5, msg=
"configuration of hand should be 0")
104 velma.moveHandLeft(dest_q, [1, 1, 1, 1], [8000, 8000, 8000, 8000], 100000000, hold=
False)
105 velma.moveHandRight(dest_q, [1.25, 1.25, 1.25, 1.25], [4000,4000,4000,4000], 1000, hold=
False)
106 if velma.waitForHandLeft() != 0:
108 if velma.waitForHandRight() != 0:
112 velma.moveHandLeft(dest_q, [1, 1, 1, 1], [8000, 8000, 8000, 8000], 100000000, hold=
False)
113 velma.moveHandRight(dest_q, [1.25, 1.25, 1.25, 1.25], [4000,4000,4000,4000], 1000, hold=
False)
114 if velma.waitForHandLeft() != 0:
116 if velma.waitForHandRight() != 0:
120 velma.moveHandLeft(dest_q, [1, 1, 1, 1], [8000, 8000, 8000, 8000], 100000000, hold=
False)
121 velma.moveHandRight(dest_q, [1.25, 1.25, 1.25, 1.25], [4000,4000,4000,4000], 1000, hold=
False)
122 if velma.waitForHandLeft() != 0:
124 if velma.waitForHandRight() != 0:
def isHandConfigurationClose(current_q, dest_q, tolerance=0.1)
Check if two configurations of robot hand are close within tolerance.