39 import roslib; roslib.load_manifest(
'velma_task_cs_ros_interface')
46 from control_msgs.msg
import FollowJointTrajectoryResult
55 if __name__ ==
"__main__":
59 q_map_0 = {
'torso_0_joint':0,
'right_arm_0_joint':0,
'right_arm_1_joint':0,
60 'right_arm_2_joint':0,
'right_arm_3_joint':0,
'right_arm_4_joint':0,
'right_arm_5_joint':0,
61 'right_arm_6_joint':0,
'left_arm_0_joint':0,
'left_arm_1_joint':0,
'left_arm_2_joint':0,
62 'left_arm_3_joint':0,
'left_arm_4_joint':0,
'left_arm_5_joint':0,
'left_arm_6_joint':0 }
65 q_map_starting = {
'torso_0_joint':0,
'right_arm_0_joint':-0.3,
'right_arm_1_joint':-1.8,
66 'right_arm_2_joint':1.25,
'right_arm_3_joint':0.85,
'right_arm_4_joint':0,
'right_arm_5_joint':-0.5,
67 'right_arm_6_joint':0,
'left_arm_0_joint':0.3,
'left_arm_1_joint':1.8,
'left_arm_2_joint':-1.25,
68 'left_arm_3_joint':-0.85,
'left_arm_4_joint':0,
'left_arm_5_joint':0.5,
'left_arm_6_joint':0 }
70 q_map_left = {
'torso_0_joint':45.0/180.0*math.pi,
'right_arm_0_joint':-0.3,
'right_arm_1_joint':-1.8,
71 'right_arm_2_joint':1.25,
'right_arm_3_joint':0.85,
'right_arm_4_joint':0,
'right_arm_5_joint':-0.5,
72 'right_arm_6_joint':0,
'left_arm_0_joint':0.3,
'left_arm_1_joint':1.8,
'left_arm_2_joint':-1.25,
73 'left_arm_3_joint':-0.85,
'left_arm_4_joint':0,
'left_arm_5_joint':0.5,
'left_arm_6_joint':0 }
75 q_map_right = {
'torso_0_joint':-45.0/180.0*math.pi,
'right_arm_0_joint':-0.3,
'right_arm_1_joint':-1.8,
76 'right_arm_2_joint':1.25,
'right_arm_3_joint':0.85,
'right_arm_4_joint':0,
'right_arm_5_joint':-0.5,
77 'right_arm_6_joint':0,
'left_arm_0_joint':0.3,
'left_arm_1_joint':1.8,
'left_arm_2_joint':-1.25,
78 'left_arm_3_joint':-0.85,
'left_arm_4_joint':0,
'left_arm_5_joint':0.5,
'left_arm_6_joint':0 }
80 rospy.init_node(
'test_jimp')
84 print "This test/tutorial executes simple motions"\
85 " in joint impedance mode. Planning is not used"\
88 print "Running python interface for Velma..." 90 print "Waiting for VelmaInterface initialization..." 91 if not velma.waitForInit(timeout_s=10.0):
92 print "Could not initialize VelmaInterface\n" 94 print "Initialization ok!\n" 96 print "Motors must be enabled every time after the robot enters safe state." 97 print "If the motors are already enabled, enabling them has no effect." 98 print "Enabling motors..." 99 if velma.enableMotors() != 0:
104 diag = velma.getCoreCsDiag()
105 if not diag.motorsReady():
106 print "Motors must be homed and ready to use for this test." 109 print "Switch to jnt_imp mode (no trajectory)..." 110 velma.moveJointImpToCurrentPos(start_time=0.5)
111 error = velma.waitForJoint()
113 print "The action should have ended without error, but the error code is", error
116 while not rospy.is_shutdown():
117 print "Checking if the starting configuration is as expected..." 119 js = velma.getLastJointState()
121 print "This test requires starting pose:" 125 print "Moving to position 0 (slowly)." 126 velma.moveJoint(q_map_0, 9.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
130 js = velma.getLastJointState()
136 print "Moving to the starting position..." 137 velma.moveJoint(q_map_starting, 9.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
138 error = velma.waitForJoint()
140 print "The action should have ended without error, but the error code is", error
144 js = velma.getLastJointState()
149 print "Moving to the left position..." 150 velma.moveJoint(q_map_left, 5.0, start_time=0.5, position_tol=20.0/180.0*math.pi)
151 error = velma.waitForJoint()
153 print "The action should have ended without error, but the error code is", error
157 js = velma.getLastJointState()
161 print "Moving to the right position..." 162 velma.moveJoint(q_map_right, 10.0, start_time=0.5, position_tol=20.0/180.0*math.pi)
163 error = velma.waitForJoint()
165 print "The action should have ended without error, but the error code is", error
169 js = velma.getLastJointState()
174 print "Moving to the starting position..." 175 velma.moveJoint(q_map_starting, 5.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
176 error = velma.waitForJoint()
178 print "The action should have ended without error, but the error code is", error
182 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.
ROS-based, Python interface class for WUT Velma Robot.