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_pose')
70 print "This test/tutorial executes simple 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 diag = velma.getCoreCsDiag()
82 if not diag.motorsReady():
83 print "Motors must be homed and ready to use for this test." 86 print "waiting for Planner init..." 87 p = Planner(velma.maxJointTrajLen())
88 if not p.waitForInit():
89 print "could not initialize PLanner" 91 print "Planner init ok" 95 print "Planning motion to the goal position using set of all joints..." 96 print "Moving to valid position, using planned trajectory." 97 goal_constraint =
qMapToConstraints(q_dest, 0.01, group=velma.getJointGroup(
"impedance_joints"))
100 js = velma.getLastJointState()
101 print "Planning (try", i,
")..." 102 traj = p.plan(js[1], [goal_constraint],
"impedance_joints", max_velocity_scaling_factor=0.15, planner_id=
"RRTConnect")
105 print "Executing trajectory..." 106 if not velma.moveJointTraj(traj, start_time=0.5):
108 if velma.waitForJoint() == 0:
111 print "The trajectory could not be completed, retrying..." 114 js = velma.getLastJointState()
119 if velma.enableMotors() != 0:
122 print "Switch to jnt_imp mode (no trajectory)..." 123 velma.moveJointImpToCurrentPos(start_time=0.2)
124 error = velma.waitForJoint()
126 print "The action should have ended without error, but the error code is", error
130 diag = velma.getCoreCsDiag()
131 if not diag.inStateJntImp():
132 print "The core_cs should be in jnt_imp state, but it is not" 135 print "Checking if the starting configuration is as expected..." 137 js = velma.getLastJointState()
139 print "This test requires starting pose:" 144 js_init = velma.getLastJointState()
148 print "Switch to cart_imp mode (no trajectory)..." 149 if not velma.moveCartImpRightCurrentPos(start_time=0.2):
151 if velma.waitForEffectorRight() != 0:
156 diag = velma.getCoreCsDiag()
157 if not diag.inStateCartImp():
158 print "The core_cs should be in cart_imp state, but it is not" 161 print "Reset tools for both arms..." 162 T_B_Wr = velma.getTf(
"B",
"Wr")
163 T_B_Wl = velma.getTf(
"B",
"Wl")
164 if not velma.moveCartImpRight([T_B_Wr], [0.1], [PyKDL.Frame()], [0.1],
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
166 if not velma.moveCartImpLeft([T_B_Wl], [0.1], [PyKDL.Frame()], [0.1],
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
168 if velma.waitForEffectorRight() != 0:
170 if velma.waitForEffectorLeft() != 0:
173 print "Moving right wrist to pose defined in world frame..." 174 T_B_Trd = PyKDL.Frame(PyKDL.Rotation.Quaternion( 0.0 , 0.0 , 0.0 , 1.0 ), PyKDL.Vector( 0.7 , -0.3 , 1.3 ))
175 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):
177 if velma.waitForEffectorRight() != 0:
180 print "calculating difference between desiread and reached pose..." 181 T_B_T_diff = PyKDL.diff(T_B_Trd, velma.getTf(
"B",
"Tr"), 1.0)
183 if T_B_T_diff.vel.Norm() > 0.05
or T_B_T_diff.rot.Norm() > 0.05:
187 print "Rotating right writs by 30 deg around local z axis (right-hand side matrix multiplication)" 188 T_B_Tr = velma.getTf(
"B",
"Tr")
189 T_B_Trd = T_B_Tr * PyKDL.Frame(PyKDL.Rotation.RotZ(30.0/180.0*math.pi))
190 if not velma.moveCartImpRight([T_B_Trd], [2.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
192 if velma.waitForEffectorRight() != 0:
196 print "Rotating right writs by 30 deg around local y 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.RotY(30.0/180.0*math.pi))
199 if not velma.moveCartImpRight([T_B_Trd], [2.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:
205 print "Rotating right writs by 30 deg around local x axis (right-hand side matrix multiplication)" 206 T_B_Tr = velma.getTf(
"B",
"Tr")
207 T_B_Trd = T_B_Tr * PyKDL.Frame(PyKDL.Rotation.RotX(30.0/180.0*math.pi))
208 if not velma.moveCartImpRight([T_B_Trd], [2.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
210 if velma.waitForEffectorRight() != 0:
216 print "Moving right wrist to pose defined in world frame..." 217 T_B_Trd = PyKDL.Frame(PyKDL.Rotation.Quaternion( 0.0 , 0.0 , 0.0 , 1.0 ), PyKDL.Vector( 0.7 , -0.3 , 1.3 ))
218 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):
220 if velma.waitForEffectorRight() != 0:
223 print "calculating difference between desiread and reached pose..." 224 T_B_T_diff = PyKDL.diff(T_B_Trd, velma.getTf(
"B",
"Tr"), 1.0)
226 if T_B_T_diff.vel.Norm() > 0.05
or T_B_T_diff.rot.Norm() > 0.05:
230 print "Rotating right writs by 30 deg around global z axis (left-hand side matrix multiplication)" 231 T_B_Tr = velma.getTf(
"B",
"Tr")
233 T_B_Trd = PyKDL.Frame(PyKDL.Rotation.RotZ(30.0/180.0*math.pi)) * T_B_Tr
234 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):
236 if velma.waitForEffectorRight() != 0:
240 print "Moving right wrist to the previous pose (cart_imp)..." 241 if not velma.moveCartImpRight([T_B_Tr_old], [3.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
243 if velma.waitForEffectorRight() != 0:
247 print "Rotating right writs by 30 deg around global z axis (left-hand side matrix multiplication for rotation only, position is constant)" 248 T_B_Tr = velma.getTf(
"B",
"Tr")
249 T_B_Trd = PyKDL.Frame( PyKDL.Rotation.RotZ(30.0/180.0*math.pi) * T_B_Tr.M, T_B_Tr.p )
250 if not velma.moveCartImpRight([T_B_Trd], [2.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
252 if velma.waitForEffectorRight() != 0:
256 print "Rotating right writs by 30 deg around global y axis (left-hand side matrix multiplication for rotation only, position is constant)" 257 T_B_Tr = velma.getTf(
"B",
"Tr")
258 T_B_Trd = PyKDL.Frame( PyKDL.Rotation.RotY(30.0/180.0*math.pi) * T_B_Tr.M, T_B_Tr.p )
259 if not velma.moveCartImpRight([T_B_Trd], [2.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
261 if velma.waitForEffectorRight() != 0:
265 print "Rotating right writs by 30 deg around global x axis (left-hand side matrix multiplication for rotation only, position is constant)" 266 T_B_Tr = velma.getTf(
"B",
"Tr")
267 T_B_Trd = PyKDL.Frame( PyKDL.Rotation.RotX(30.0/180.0*math.pi) * T_B_Tr.M, T_B_Tr.p )
268 if not velma.moveCartImpRight([T_B_Trd], [2.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), start_time=0.5):
270 if velma.waitForEffectorRight() != 0:
276 print "Switch to cart_imp mode (no trajectory)..." 277 if not velma.moveCartImpRightCurrentPos(start_time=0.2):
279 if velma.waitForEffectorRight() != 0:
282 print "Rotating right writs by 45 deg around local z axis and left wrist by -45 deg (right-hand side matrix multiplication)" 283 synchronized_time = rospy.Time.now() + rospy.Duration(0.5)
284 T_B_Tr = velma.getTf(
"B",
"Tr")
285 T_B_Trd = T_B_Tr * PyKDL.Frame(PyKDL.Rotation.RotZ(30.0/180.0*math.pi))
286 T_B_Tl = velma.getTf(
"B",
"Tl")
287 T_B_Tld = T_B_Tl * PyKDL.Frame(PyKDL.Rotation.RotZ(-30.0/180.0*math.pi))
288 if not velma.moveCartImpRight([T_B_Trd], [2.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), stamp=synchronized_time):
290 if not velma.moveCartImpLeft([T_B_Tld], [2.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), stamp=synchronized_time):
292 if velma.waitForEffectorRight() != 0:
294 if velma.waitForEffectorLeft() != 0:
298 print "Rotating both writs by 30 deg around local x axis (right-hand side matrix multiplication)" 299 synchronized_time = rospy.Time.now() + rospy.Duration(0.5)
300 T_B_Tr = velma.getTf(
"B",
"Tr")
301 T_B_Trd = T_B_Tr * PyKDL.Frame(PyKDL.Rotation.RotX(30.0/180.0*math.pi))
302 T_B_Tl = velma.getTf(
"B",
"Tl")
303 T_B_Tld = T_B_Tl * PyKDL.Frame(PyKDL.Rotation.RotX(30.0/180.0*math.pi))
304 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)), stamp=synchronized_time):
306 if not velma.moveCartImpLeft([T_B_Tld, T_B_Tl], [2.0, 4.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), stamp=synchronized_time):
308 if velma.waitForEffectorRight() != 0:
310 if velma.waitForEffectorLeft() != 0:
314 print "Rotating right writs by 30 deg around global x axis (left-hand side matrix multiplication for rotation only, position is constant)" 315 synchronized_time = rospy.Time.now() + rospy.Duration(0.5)
316 T_B_Tr = velma.getTf(
"B",
"Tr")
317 T_B_Trd = PyKDL.Frame( PyKDL.Rotation.RotX(30.0/180.0*math.pi) * T_B_Tr.M, T_B_Tr.p )
318 T_B_Tl = velma.getTf(
"B",
"Tl")
319 T_B_Tld = PyKDL.Frame( PyKDL.Rotation.RotX(30.0/180.0*math.pi) * T_B_Tl.M, T_B_Tl.p )
320 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)), stamp=synchronized_time):
322 if not velma.moveCartImpLeft([T_B_Tld, T_B_Tl], [2.0, 4.0],
None,
None,
None,
None, PyKDL.Wrench(PyKDL.Vector(5,5,5), PyKDL.Vector(5,5,5)), stamp=synchronized_time):
324 if velma.waitForEffectorRight() != 0:
326 if velma.waitForEffectorLeft() != 0:
def planAndExecute(q_dest)
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.