37 import roslib; roslib.load_manifest(
'velma_task_cs_ros_interface')
41 from velma_common
import VelmaInterface
42 from rcprg_ros_utils
import exitError
45 return float(deg)/180.0*math.pi
49 print(
'set_gripper_configuration left|right reset')
50 print(
'set_gripper_configuration left|right <q_f1_deg> <q_f2_deg> <q_f3_deg> <q_spread_deg>')
52 if __name__ ==
"__main__":
55 if len(sys.argv) == 6:
56 q_f1_deg = float(sys.argv[2])
57 q_f2_deg = float(sys.argv[3])
58 q_f3_deg = float(sys.argv[4])
59 q_spread_deg = float(sys.argv[5])
60 elif len(sys.argv) == 3
and sys.argv[2] ==
'reset':
67 if side !=
'left' and side !=
'right':
69 exitError(2, msg=
'Wrong side: "{}"'.format(side))
71 rospy.init_node(
'set_gripper_configuration', anonymous=
False)
73 print "waiting for init..." 75 velma = VelmaInterface()
77 print "Waiting for VelmaInterface initialization..." 78 if not velma.waitForInit(timeout_s=10.0):
79 print "Could not initialize VelmaInterface\n" 82 print "Initialization ok!\n" 84 diag = velma.getCoreCsDiag()
85 if (
not diag.inStateCartImp())
and (
not diag.inStateJntImp()):
86 exitError(4, msg=
'Velma should be in cart_imp or jnt_imp state')
90 if velma.waitForHand(side) != 0:
95 velma.moveHand(side, q, [1, 1, 1, 1], [4000,4000,4000,4000], 1000, hold=
False)
96 if velma.waitForHand(side) != 0: