WUT Velma robot API
test_cimp_tool.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 
7 
8 # Copyright (c) 2017, Robot Control and Pattern Recognition Group,
9 # Institute of Control and Computation Engineering
10 # Warsaw University of Technology
11 #
12 # All rights reserved.
13 #
14 # Redistribution and use in source and binary forms, with or without
15 # modification, are permitted provided that the following conditions are met:
16 # * Redistributions of source code must retain the above copyright
17 # notice, this list of conditions and the following disclaimer.
18 # * Redistributions in binary form must reproduce the above copyright
19 # notice, this list of conditions and the following disclaimer in the
20 # documentation and/or other materials provided with the distribution.
21 # * Neither the name of the Warsaw University of Technology nor the
22 # names of its contributors may be used to endorse or promote products
23 # derived from this software without specific prior written permission.
24 #
25 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
26 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
27 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
28 # DISCLAIMED. IN NO EVENT SHALL <COPYright HOLDER> BE LIABLE FOR ANY
29 # DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
30 # (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
32 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
33 # (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
34 # SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
35 #
36 # Author: Dawid Seredynski
37 #
38 
39 import roslib; roslib.load_manifest('velma_task_cs_ros_interface')
40 import rospy
41 
42 from velma_common import *
43 from rcprg_planner import *
44 from rcprg_ros_utils import exitError
45 
46 if __name__ == "__main__":
47  # define some configurations
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 }
56 
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 }
65 
66  rospy.init_node('test_cimp_tool')
67 
68  rospy.sleep(0.5)
69 
70  print "This test/tutorial executes simple tool motions"\
71  " in Cartesian impedance mode.\n"
72 
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"
78  exitError(1)
79  print "Initialization ok!\n"
80 
81  if velma.enableMotors() != 0:
82  exitError(2)
83 
84  diag = velma.getCoreCsDiag()
85  if not diag.motorsReady():
86  print "Motors must be homed and ready to use for this test."
87  exitError(3)
88 
89  print "waiting for Planner init..."
90  p = Planner(velma.maxJointTrajLen())
91  if not p.waitForInit():
92  print "could not initialize PLanner"
93  exitError(4)
94  print "Planner init ok"
95 
96  # define a function for frequently used routine in this test
97  def planAndExecute(q_dest):
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"))
101  for i in range(5):
102  rospy.sleep(0.5)
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")
106  if traj == None:
107  continue
108  print "Executing trajectory..."
109  if not velma.moveJointTraj(traj, start_time=0.5):
110  exitError(5)
111  if velma.waitForJoint() == 0:
112  break
113  else:
114  print "The trajectory could not be completed, retrying..."
115  continue
116  rospy.sleep(0.5)
117  js = velma.getLastJointState()
118  if not isConfigurationClose(q_dest, js[1]):
119  exitError(6)
120 
121  print "Switch to jnt_imp mode (no trajectory)..."
122  velma.moveJointImpToCurrentPos(start_time=0.2)
123  error = velma.waitForJoint()
124  if error != 0:
125  print "The action should have ended without error, but the error code is", error
126  exitError(7)
127 
128  rospy.sleep(0.5)
129  diag = velma.getCoreCsDiag()
130  if not diag.inStateJntImp():
131  print "The core_cs should be in jnt_imp state, but it is not"
132  exitError(8)
133 
134  print "Checking if the starting configuration is as expected..."
135  rospy.sleep(0.5)
136  js = velma.getLastJointState()
137  if not isConfigurationClose(q_map_starting, js[1], tolerance=0.2):
138  print "This test requires starting pose:"
139  print q_map_starting
140  exitError(9)
141 
142  # get initial configuration
143  js_init = velma.getLastJointState()
144 
145  planAndExecute(q_map_1)
146 
147  print "Switch to cart_imp mode (no trajectory)..."
148  if not velma.moveCartImpRightCurrentPos(start_time=0.2):
149  exitError(10)
150  if velma.waitForEffectorRight() != 0:
151  exitError(11)
152 
153  rospy.sleep(0.5)
154 
155  diag = velma.getCoreCsDiag()
156  if not diag.inStateCartImp():
157  print "The core_cs should be in cart_imp state, but it is not"
158  exitError(12)
159 
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"
162 
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):
166  exitError(13)
167  if velma.waitForEffectorRight() != 0:
168  exitError(14)
169  rospy.sleep(0.5)
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)
172  print T_B_T_diff
173  if T_B_T_diff.vel.Norm() > 0.05 or T_B_T_diff.rot.Norm() > 0.05:
174  exitError(15)
175 
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):
180  exitError(16)
181  if velma.waitForEffectorRight() != 0:
182  exitError(17)
183  rospy.sleep(0.5)
184 
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):
189  exitError(18)
190  if velma.waitForEffectorRight() != 0:
191  exitError(19)
192 
193  print "the right tool is now in 'grip' pose"
194  rospy.sleep(0.5)
195 
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):
200  exitError(20)
201  if velma.waitForEffectorRight() != 0:
202  exitError(21)
203  rospy.sleep(0.5)
204 
205  planAndExecute(q_map_starting)
206 
207  exitError(0)
208 
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 planAndExecute(q_dest)