39 import roslib; roslib.load_manifest(
'velma_task_cs_ros_interface')
42 from velma_common
import *
43 from rcprg_planner
import *
44 from rcprg_ros_utils
import exitError
46 if __name__ ==
"__main__":
48 q_map_starting = {
'torso_0_joint':0,
49 'right_arm_0_joint':-0.3,
'left_arm_0_joint':0.3,
50 'right_arm_1_joint':-1.8,
'left_arm_1_joint':1.8,
51 'right_arm_2_joint':1.25,
'left_arm_2_joint':-1.25,
52 'right_arm_3_joint':0.85,
'left_arm_3_joint':-0.85,
53 'right_arm_4_joint':0,
'left_arm_4_joint':0,
54 'right_arm_5_joint':-0.5,
'left_arm_5_joint':0.5,
55 'right_arm_6_joint':0,
'left_arm_6_joint':0 }
57 q_map_1 = {
'torso_0_joint':0.0,
58 'right_arm_0_joint':-0.3,
'left_arm_0_joint':0.3,
59 'right_arm_1_joint':-1.57,
'left_arm_1_joint':1.57,
60 'right_arm_2_joint':1.57,
'left_arm_2_joint':-1.57,
61 'right_arm_3_joint':1.57,
'left_arm_3_joint':-1.7,
62 'right_arm_4_joint':0.0,
'left_arm_4_joint':0.0,
63 'right_arm_5_joint':-1.57,
'left_arm_5_joint':1.57,
64 'right_arm_6_joint':0.0,
'left_arm_6_joint':0.0 }
66 rospy.init_node(
'test_cimp_tool')
70 print "This test/tutorial executes simple tool motions"\
71 " in Cartesian impedance mode.\n" 73 print "Running python interface for Velma..." 74 velma = VelmaInterface()
75 print "Waiting for VelmaInterface initialization..." 76 if not velma.waitForInit(timeout_s=10.0):
77 print "Could not initialize VelmaInterface\n" 79 print "Initialization ok!\n" 81 if velma.enableMotors() != 0:
84 diag = velma.getCoreCsDiag()
85 if not diag.motorsReady():
86 print "Motors must be homed and ready to use for this test." 89 print "waiting for Planner init..." 90 p = Planner(velma.maxJointTrajLen())
91 if not p.waitForInit():
92 print "could not initialize PLanner" 94 print "Planner init ok" 98 print "Planning motion to the goal position using set of all joints..." 99 print "Moving to valid position, using planned trajectory." 100 goal_constraint =
qMapToConstraints(q_dest, 0.01, group=velma.getJointGroup(
"impedance_joints"))
103 js = velma.getLastJointState()
104 print "Planning (try", i,
")..." 105 traj = p.plan(js[1], [goal_constraint],
"impedance_joints", max_velocity_scaling_factor=0.15, planner_id=
"RRTConnect")
108 print "Executing trajectory..." 109 if not velma.moveJointTraj(traj, start_time=0.5):
111 if velma.waitForJoint() == 0:
114 print "The trajectory could not be completed, retrying..." 117 js = velma.getLastJointState()
121 print "Switch to jnt_imp mode (no trajectory)..." 122 velma.moveJointImpToCurrentPos(start_time=0.2)
123 error = velma.waitForJoint()
125 print "The action should have ended without error, but the error code is", error
129 diag = velma.getCoreCsDiag()
130 if not diag.inStateJntImp():
131 print "The core_cs should be in jnt_imp state, but it is not" 134 print "Checking if the starting configuration is as expected..." 136 js = velma.getLastJointState()
138 print "This test requires starting pose:" 143 js_init = velma.getLastJointState()
147 print "Switch to cart_imp mode (no trajectory)..." 148 if not velma.moveCartImpRightCurrentPos(start_time=0.2):
150 if velma.waitForEffectorRight() != 0:
155 diag = velma.getCoreCsDiag()
156 if not diag.inStateCartImp():
157 print "The core_cs should be in cart_imp state, but it is not" 160 print "To see the tool frame add 'tf' in rviz and enable 'right_arm_tool' frame." 161 print "At every state switch to cart_imp, the tool frames are reset" 163 print "Moving right wrist to pose defined in world frame..." 164 T_B_Trd = PyKDL.Frame(PyKDL.Rotation.Quaternion( 0.0 , 0.0 , 0.0 , 1.0 ), PyKDL.Vector( 0.7 , -0.3 , 1.3 ))
165 if not velma.moveCartImpRight([T_B_Trd], [3.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
167 if velma.waitForEffectorRight() != 0:
170 print "Calculating difference between desiread and reached pose..." 171 T_B_T_diff = PyKDL.diff(T_B_Trd, velma.getTf(
"B",
"Tr"), 1.0)
173 if T_B_T_diff.vel.Norm() > 0.05
or T_B_T_diff.rot.Norm() > 0.05:
176 print "Rotating right writs by 45 deg around local z axis (right-hand side matrix multiplication)" 177 T_B_Tr = velma.getTf(
"B",
"Tr")
178 T_B_Trd = T_B_Tr * PyKDL.Frame(PyKDL.Rotation.RotZ(45.0/180.0*math.pi))
179 if not velma.moveCartImpRight([T_B_Trd, T_B_Tr], [2.0, 4.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
181 if velma.waitForEffectorRight() != 0:
185 print "Moving the right tool and equilibrium pose from 'wrist' to 'grip' frame..." 186 T_B_Wr = velma.getTf(
"B",
"Wr")
187 T_Wr_Gr = velma.getTf(
"Wr",
"Gr")
188 if not velma.moveCartImpRight([T_B_Wr*T_Wr_Gr], [0.1], [T_Wr_Gr], [0.1],
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
190 if velma.waitForEffectorRight() != 0:
193 print "the right tool is now in 'grip' pose" 196 print "Rotating right equilibrium pose by -45 deg around local x axis (right-hand side matrix multiplication)" 197 T_B_Tr = velma.getTf(
"B",
"Tr")
198 T_B_Trd = T_B_Tr * PyKDL.Frame(PyKDL.Rotation.RotX(-45.0/180.0*math.pi))
199 if not velma.moveCartImpRight([T_B_Trd, T_B_Tr], [2.0, 4.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
201 if velma.waitForEffectorRight() != 0:
def qMapToConstraints(q_map, tolerance=0.01, group=None)
This function converts dictionary of joint positions to moveit_msgs.Constraints structure.
def isConfigurationClose(q_map1, q_map2, tolerance=0.1, allow_subset=False)
Check if two configurations of robot body are close within tolerance.