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_imp')
70 print "This test/tutorial executes simple impedance commands"\
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()
122 return PyKDL.Wrench(PyKDL.Vector(lx,ly,lz), PyKDL.Vector(rx,ry,rz))
124 print "Switch to jnt_imp mode (no trajectory)..." 125 velma.moveJointImpToCurrentPos(start_time=0.2)
126 error = velma.waitForJoint()
128 print "The action should have ended without error, but the error code is", error
132 diag = velma.getCoreCsDiag()
133 if not diag.inStateJntImp():
134 print "The core_cs should be in jnt_imp state, but it is not" 137 print "Checking if the starting configuration is as expected..." 139 js = velma.getLastJointState()
141 print "This test requires starting pose:" 146 js_init = velma.getLastJointState()
150 print "Switch to cart_imp mode (no trajectory)..." 151 if not velma.moveCartImpRightCurrentPos(start_time=0.2):
153 if velma.waitForEffectorRight() != 0:
158 diag = velma.getCoreCsDiag()
159 if not diag.inStateCartImp():
160 print "The core_cs should be in cart_imp state, but it is not" 163 print "To see the tool frame add 'tf' in rviz and enable 'right_arm_tool' frame." 164 print "At every state switch to cart_imp, the tool frames are reset." 165 print "Also, the tool impedance parameters are reset to 1500N/m in every"\
166 " direction for linear stiffness and to 150Nm/rad in every direction for angular"\
167 " stiffness, i.e. (1500,1500,1500,150,150,150)." 169 print "Moving right wrist to pose defined in world frame..." 170 T_B_Trd = PyKDL.Frame(PyKDL.Rotation.Quaternion( 0.0 , 0.0 , 0.0 , 1.0 ), PyKDL.Vector( 0.7 , -0.3 , 1.3 ))
171 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):
173 if velma.waitForEffectorRight() != 0:
176 print "Calculating difference between desiread and reached pose..." 177 T_B_T_diff = PyKDL.diff(T_B_Trd, velma.getTf(
"B",
"Tr"), 1.0)
179 if T_B_T_diff.vel.Norm() > 0.05
or T_B_T_diff.rot.Norm() > 0.05:
182 print "Set impedance to (1000,1000,125,150,150,150) in tool frame." 187 if not velma.moveCartImpRight(
None,
None,
None,
None, imp_list, [0.5,1.0,1.5,2.0], PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
189 if velma.waitForEffectorRight() != 0:
194 print "Set impedance to (1000,1000,1000,150,150,150) in tool frame." 195 imp_list = [
makeWrench(1000,1000,250,150,150,150),
198 if not velma.moveCartImpRight(
None,
None,
None,
None, imp_list, [0.5,1.0,1.5], PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
200 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.
def makeWrench(lx, ly, lz, rx, ry, rz)
def planAndExecute(q_dest)