37 import roslib; roslib.load_manifest(
'velma_task_cs_ros_interface')
42 from velma_common
import *
43 from rcprg_ros_utils
import exitError
45 if __name__ ==
"__main__":
47 rospy.init_node(
'head_test', anonymous=
False)
51 print "This test/tutorial executes simple motions"\
54 print "Running python interface for Velma..." 55 velma = VelmaInterface()
56 print "Waiting for VelmaInterface initialization..." 57 if not velma.waitForInit(timeout_s=10.0):
58 print "Could not initialize VelmaInterface\n" 60 print "Initialization ok!\n" 62 diag = velma.getCoreCsDiag()
63 if not diag.motorsReady():
64 print "Motors must be homed and ready to use for this test." 67 print "Motors must be enabled every time after the robot enters safe state." 68 print "If the motors are already enabled, enabling them has no effect." 69 print "Enabling motors..." 70 if velma.enableMotors() != 0:
80 print(
'Switch to jnt_imp mode (no trajectory)...')
81 velma.moveJointImpToCurrentPos(start_time=0.5)
82 error = velma.waitForJoint()
85 exitError(4, msg=
'The action should have ended without error,'\
86 ' but the error code is {}'.format(error))
88 print "moving head to position: 0" 90 velma.moveHead(q_dest, 4.0, start_time=0.5)
91 if velma.waitForHead() != 0:
def isHeadConfigurationClose(q1, q2, tolerance=0.1)
Check if two configurations of robot neck are close within tolerance.