WUT Velma robot API
test_jimp_planning.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 
41 import rospy
42 import math
43 import PyKDL
44 
45 from velma_common import *
46 from rcprg_planner import *
47 from rcprg_ros_utils import exitError
48 
49 if __name__ == "__main__":
50  # define some configurations
51  q_map_starting = {'torso_0_joint':0, 'right_arm_0_joint':-0.3, 'right_arm_1_joint':-1.8,
52  'right_arm_2_joint':1.25, 'right_arm_3_joint':0.85, 'right_arm_4_joint':0, 'right_arm_5_joint':-0.5,
53  'right_arm_6_joint':0, 'left_arm_0_joint':0.3, 'left_arm_1_joint':1.8, 'left_arm_2_joint':-1.25,
54  'left_arm_3_joint':-0.85, 'left_arm_4_joint':0, 'left_arm_5_joint':0.5, 'left_arm_6_joint':0 }
55 
56  q_map_goal = {'torso_0_joint':0, 'right_arm_0_joint':-0.3, 'right_arm_1_joint':-1.8,
57  'right_arm_2_joint':-1.25, 'right_arm_3_joint':1.57, 'right_arm_4_joint':0, 'right_arm_5_joint':-0.5,
58  'right_arm_6_joint':0, 'left_arm_0_joint':0.3, 'left_arm_1_joint':1.8, 'left_arm_2_joint':-1.25,
59  'left_arm_3_joint':-0.85, 'left_arm_4_joint':0, 'left_arm_5_joint':0.5, 'left_arm_6_joint':0 }
60 
61  rospy.init_node('test_jimp_planning', anonymous=False)
62 
63  rospy.sleep(0.5)
64 
65  print "This test/tutorial executes complex motions"\
66  " in Joint Impedance mode. Planning is used"\
67  " in this example.\n"
68 
69  print "Running python interface for Velma..."
70  velma = VelmaInterface()
71  print "Waiting for VelmaInterface initialization..."
72  if not velma.waitForInit(timeout_s=10.0):
73  print "Could not initialize VelmaInterface\n"
74  exitError(1)
75  print "Initialization ok!\n"
76 
77  diag = velma.getCoreCsDiag()
78  if not diag.motorsReady():
79  print "Motors must be homed and ready to use for this test."
80  exitError(1)
81 
82  print "Waiting for Planner initialization..."
83  p = Planner(velma.maxJointTrajLen())
84  if not p.waitForInit(timeout_s=10.0):
85  print "Could not initialize Planner"
86  exitError(2)
87  print "Planner initialization ok!"
88 
89  print "Motors must be enabled every time after the robot enters safe state."
90  print "If the motors are already enabled, enabling them has no effect."
91  print "Enabling motors..."
92  if velma.enableMotors() != 0:
93  exitError(3)
94 
95  print "Switch to jnt_imp mode (no trajectory)..."
96  velma.moveJointImpToCurrentPos(start_time=0.5)
97  error = velma.waitForJoint()
98  if error != 0:
99  print "The action should have ended without error, but the error code is", error
100  exitError(4)
101 
102  print "Checking if the starting configuration is as expected..."
103  rospy.sleep(0.5)
104  js = velma.getLastJointState()
105  if not isConfigurationClose(q_map_starting, js[1], tolerance=0.2):
106  print "This test requires starting pose:"
107  print q_map_starting
108  exitError(10)
109 
110  print "Planning motion to the goal position using set of all joints..."
111 
112  print "Moving to valid position, using planned trajectory."
113  goal_constraint_1 = qMapToConstraints(q_map_goal, 0.01, group=velma.getJointGroup("impedance_joints"))
114  for i in range(15):
115  rospy.sleep(0.5)
116  js = velma.getLastJointState()
117  print "Planning (try", i, ")..."
118  traj = p.plan(js[1], [goal_constraint_1], "impedance_joints", num_planning_attempts=10, max_velocity_scaling_factor=0.15, planner_id="RRTConnect")
119  if traj == None:
120  continue
121  print "Executing trajectory..."
122  if not velma.moveJointTraj(traj, start_time=0.5, position_tol=10.0/180.0 * math.pi, velocity_tol=10.0/180.0*math.pi):
123  exitError(5)
124  if velma.waitForJoint() == 0:
125  break
126  else:
127  print "The trajectory could not be completed, retrying..."
128  continue
129 
130  rospy.sleep(0.5)
131  js = velma.getLastJointState()
132  if not isConfigurationClose(q_map_goal, js[1]):
133  exitError(6)
134 
135  rospy.sleep(1.0)
136 
137  print "Moving to starting position, using planned trajectory."
138  goal_constraint_2 = qMapToConstraints(q_map_starting, 0.01, group=velma.getJointGroup("impedance_joints"))
139  for i in range(15):
140  rospy.sleep(0.5)
141  js = velma.getLastJointState()
142  print "Planning (try", i, ")..."
143  traj = p.plan(js[1], [goal_constraint_2], "impedance_joints", num_planning_attempts=10, max_velocity_scaling_factor=0.15, planner_id="RRTConnect")
144  if traj == None:
145  continue
146  print "Executing trajectory..."
147  if not velma.moveJointTraj(traj, start_time=0.5, position_tol=10.0/180.0 * math.pi, velocity_tol=10.0/180.0*math.pi):
148  exitError(7)
149  if velma.waitForJoint() == 0:
150  break
151  else:
152  print "The trajectory could not be completed, retrying..."
153  continue
154  rospy.sleep(0.5)
155  js = velma.getLastJointState()
156  if not isConfigurationClose(q_map_starting, js[1]):
157  exitError(8)
158 
159  print "Planning motion to the same goal position using subset of joints (right arm only)..."
160 
161  print "Moving to valid position, using planned trajectory."
162  goal_constraint_1 = qMapToConstraints(q_map_goal, 0.01, group=velma.getJointGroup("right_arm"))
163  for i in range(15):
164  rospy.sleep(0.5)
165  js = velma.getLastJointState()
166  print "Planning (try", i, ")..."
167  traj = p.plan(js[1], [goal_constraint_1], "right_arm", num_planning_attempts=10, max_velocity_scaling_factor=0.15, planner_id="RRTConnect")
168  if traj == None:
169  continue
170  print "Executing trajectory..."
171  if not velma.moveJointTraj(traj, start_time=0.5, position_tol=10.0/180.0 * math.pi, velocity_tol=10.0/180.0*math.pi):
172  exitError(9)
173  if velma.waitForJoint() == 0:
174  break
175  else:
176  print "The trajectory could not be completed, retrying..."
177  continue
178 
179  rospy.sleep(0.5)
180  js = velma.getLastJointState()
181  if not isConfigurationClose(q_map_goal, js[1]):
182  exitError(10)
183 
184  rospy.sleep(1.0)
185 
186  print "Moving to starting position, using planned trajectory."
187  goal_constraint_2 = qMapToConstraints(q_map_starting, 0.01, group=velma.getJointGroup("right_arm"))
188  for i in range(15):
189  rospy.sleep(0.5)
190  js = velma.getLastJointState()
191  print "Planning (try", i, ")..."
192  traj = p.plan(js[1], [goal_constraint_2], "right_arm", num_planning_attempts=10, max_velocity_scaling_factor=0.15, planner_id="RRTConnect")
193  if traj == None:
194  continue
195  print "Executing trajectory..."
196  if not velma.moveJointTraj(traj, start_time=0.5, position_tol=10.0/180.0 * math.pi, velocity_tol=10.0/180.0*math.pi):
197  exitError(11)
198  if velma.waitForJoint() == 0:
199  break
200  else:
201  print "The trajectory could not be completed, retrying..."
202  continue
203  rospy.sleep(0.5)
204  js = velma.getLastJointState()
205  if not isConfigurationClose(q_map_starting, js[1]):
206  exitError(12)
207 
208  exitError(0)
209 
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.