WUT Velma robot API
test_cimp_imp.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_imp')
67 
68  rospy.sleep(0.5)
69 
70  print "This test/tutorial executes simple impedance commands"\
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  def makeWrench(lx,ly,lz,rx,ry,rz):
122  return PyKDL.Wrench(PyKDL.Vector(lx,ly,lz), PyKDL.Vector(rx,ry,rz))
123 
124  print "Switch to jnt_imp mode (no trajectory)..."
125  velma.moveJointImpToCurrentPos(start_time=0.2)
126  error = velma.waitForJoint()
127  if error != 0:
128  print "The action should have ended without error, but the error code is", error
129  exitError(7)
130 
131  rospy.sleep(0.5)
132  diag = velma.getCoreCsDiag()
133  if not diag.inStateJntImp():
134  print "The core_cs should be in jnt_imp state, but it is not"
135  exitError(8)
136 
137  print "Checking if the starting configuration is as expected..."
138  rospy.sleep(0.5)
139  js = velma.getLastJointState()
140  if not isConfigurationClose(q_map_starting, js[1], tolerance=0.2):
141  print "This test requires starting pose:"
142  print q_map_starting
143  exitError(9)
144 
145  # get initial configuration
146  js_init = velma.getLastJointState()
147 
148  planAndExecute(q_map_1)
149 
150  print "Switch to cart_imp mode (no trajectory)..."
151  if not velma.moveCartImpRightCurrentPos(start_time=0.2):
152  exitError(10)
153  if velma.waitForEffectorRight() != 0:
154  exitError(11)
155 
156  rospy.sleep(0.5)
157 
158  diag = velma.getCoreCsDiag()
159  if not diag.inStateCartImp():
160  print "The core_cs should be in cart_imp state, but it is not"
161  exitError(12)
162 
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)."
168 
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):
172  exitError(13)
173  if velma.waitForEffectorRight() != 0:
174  exitError(14)
175  rospy.sleep(0.5)
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)
178  print T_B_T_diff
179  if T_B_T_diff.vel.Norm() > 0.05 or T_B_T_diff.rot.Norm() > 0.05:
180  exitError(15)
181 
182  print "Set impedance to (1000,1000,125,150,150,150) in tool frame."
183  imp_list = [makeWrench(1000,1000,1000,150,150,150),
184  makeWrench(1000,1000,500,150,150,150),
185  makeWrench(1000,1000,250,150,150,150),
186  makeWrench(1000,1000,125,150,150,150)]
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):
188  exitError(16)
189  if velma.waitForEffectorRight() != 0:
190  exitError(17)
191 
192  rospy.sleep(1.0)
193 
194  print "Set impedance to (1000,1000,1000,150,150,150) in tool frame."
195  imp_list = [makeWrench(1000,1000,250,150,150,150),
196  makeWrench(1000,1000,500,150,150,150),
197  makeWrench(1000,1000,1000,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):
199  exitError(16)
200  if velma.waitForEffectorRight() != 0:
201  exitError(17)
202 
203  planAndExecute(q_map_starting)
204 
205  exitError(0)
206 
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)