39 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 q_map_starting = {
'torso_0_joint':0,
'right_arm_0_joint':-0.3,
'right_arm_1_joint':-1.8,
48 'right_arm_2_joint':1.25,
'right_arm_3_joint':0.85,
'right_arm_4_joint':0,
'right_arm_5_joint':-0.5,
49 'right_arm_6_joint':0,
'left_arm_0_joint':0.3,
'left_arm_1_joint':1.8,
'left_arm_2_joint':-1.25,
50 'left_arm_3_joint':-0.85,
'left_arm_4_joint':0,
'left_arm_5_joint':0.5,
'left_arm_6_joint':0 }
52 rospy.init_node(
'test_relax', anonymous=
False)
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 "Switching to relax behavior..." 77 velma.switchToRelaxBehavior()
81 diag = velma.getCoreCsDiag()
82 if not diag.inStateRelax():
87 print "Moving to the starting position (jnt_imp)..." 88 velma.moveJoint(q_map_starting, 2.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
89 error = velma.waitForJoint()
91 print "The action should have ended without error, but the error code is", error
95 js = velma.getLastJointState()
def isConfigurationClose(q_map1, q_map2, tolerance=0.1, allow_subset=False)
Check if two configurations of robot body are close within tolerance.