WUT Velma robot API
test_jimp_planning_attached.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 from threading import Thread
45 
46 from velma_common import *
47 from rcprg_planner import *
48 from rcprg_ros_utils import MarkerPublisher, exitError
49 
50 from moveit_msgs.msg import AttachedCollisionObject, CollisionObject
51 from shape_msgs.msg import SolidPrimitive
52 from geometry_msgs.msg import Pose
53 from visualization_msgs.msg import Marker
54 import tf_conversions.posemath as pm
55 
57  def threaded_function(self, obj):
58  pub = MarkerPublisher("attached_objects")
59  while not self.stop_thread:
60  pub.publishSinglePointMarker(PyKDL.Vector(), 1, r=1, g=0, b=0, a=1, namespace='default', frame_id=obj.link_name, m_type=Marker.CYLINDER, scale=Vector3(0.02, 0.02, 1.0), T=pm.fromMsg(obj.object.primitive_poses[0]))
61  try:
62  rospy.sleep(0.1)
63  except:
64  break
65 
66  try:
67  pub.eraseMarkers(0, 10, namespace='default')
68  rospy.sleep(0.5)
69  except:
70  pass
71 
72  def __init__(self, obj):
73  self.thread = Thread(target = self.threaded_function, args = (obj, ))
74 
75  def start(self):
76  self.stop_thread = False
77  self.thread.start()
78 
79  def stop(self):
80  self.stop_thread = True
81  self.thread.join()
82 
83 if __name__ == "__main__":
84 
85  rospy.init_node('test_jimp_planning_attached', anonymous=False)
86 
87  rospy.sleep(0.5)
88 
89  print "This test/tutorial executes complex motions"\
90  " in Joint Impedance mode with additional objects"\
91  " attached to end-effectors. Planning is used"\
92  " in this example.\n"
93 
94  print "Running python interface for Velma..."
95  velma = VelmaInterface()
96  print "Waiting for VelmaInterface initialization..."
97  if not velma.waitForInit(timeout_s=10.0):
98  print "Could not initialize VelmaInterface\n"
99  exitError(1)
100  print "Initialization ok!\n"
101 
102  diag = velma.getCoreCsDiag()
103  if not diag.motorsReady():
104  print "Motors must be homed and ready to use for this test."
105  exitError(1)
106 
107  print "Waiting for Planner initialization..."
108  p = Planner(velma.maxJointTrajLen())
109  if not p.waitForInit(timeout_s=10.0):
110  print "Could not initialize Planner"
111  exitError(2)
112  print "Planner initialization ok!"
113 
114  print "Motors must be enabled every time after the robot enters safe state."
115  print "If the motors are already enabled, enabling them has no effect."
116  print "Enabling motors..."
117  if velma.enableMotors() != 0:
118  exitError(3)
119 
120  print "Moving to the current position..."
121  js_start = velma.getLastJointState()
122  velma.moveJoint(js_start[1], 1.0, start_time=0.5, position_tol=15.0/180.0*math.pi)
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(4)
127 
128  print "Creating a virtual object attached to gripper..."
129 
130  # for more details refer to ROS docs for moveit_msgs/AttachedCollisionObject
131  object1 = AttachedCollisionObject()
132  object1.link_name = "right_HandGripLink"
133  object1.object.header.frame_id = "right_HandGripLink"
134  object1.object.id = "object1"
135  object1_prim = SolidPrimitive()
136  object1_prim.type = SolidPrimitive.CYLINDER
137  object1_prim.dimensions=[None, None] # set initial size of the list to 2
138  object1_prim.dimensions[SolidPrimitive.CYLINDER_HEIGHT] = 1.0
139  object1_prim.dimensions[SolidPrimitive.CYLINDER_RADIUS] = 0.02
140  object1_pose = pm.toMsg(PyKDL.Frame(PyKDL.Rotation.RotY(math.pi/2)))
141  object1.object.primitives.append(object1_prim)
142  object1.object.primitive_poses.append(object1_pose)
143  object1.object.operation = CollisionObject.ADD
144  object1.touch_links = ['right_HandPalmLink',
145  'right_HandFingerOneKnuckleOneLink',
146  'right_HandFingerOneKnuckleTwoLink',
147  'right_HandFingerOneKnuckleThreeLink',
148  'right_HandFingerTwoKnuckleOneLink',
149  'right_HandFingerTwoKnuckleTwoLink',
150  'right_HandFingerTwoKnuckleThreeLink',
151  'right_HandFingerThreeKnuckleTwoLink',
152  'right_HandFingerThreeKnuckleThreeLink']
153 
154  print "Publishing the attached object marker on topic /attached_objects"
155  pub = MarkerPublisherThread(object1)
156  pub.start()
157 
158  q_map_goal = {'torso_0_joint':0,
159  'right_arm_0_joint':-0.3,
160  'right_arm_1_joint':-1.8,
161  'right_arm_2_joint':-1.25,
162  'right_arm_3_joint':1.57,
163  'right_arm_4_joint':0,
164  'right_arm_5_joint':-0.5,
165  'right_arm_6_joint':0,
166  'left_arm_0_joint':0.3,
167  'left_arm_1_joint':1.8,
168  'left_arm_2_joint':-1.25,
169  'left_arm_3_joint':-0.85,
170  'left_arm_4_joint':0,
171  'left_arm_5_joint':0.5,
172  'left_arm_6_joint':0
173  }
174 
175  print "Planning motion to the goal position using set of all joints..."
176 
177  print "Moving to valid position, using planned trajectory."
178  goal_constraint_1 = qMapToConstraints(q_map_goal, 0.01, group=velma.getJointGroup("impedance_joints"))
179  for i in range(3):
180  rospy.sleep(0.5)
181  js = velma.getLastJointState()
182  print "Planning (try", i, ")..."
183  traj = p.plan(js[1], [goal_constraint_1], "impedance_joints", max_velocity_scaling_factor=0.15, planner_id="RRTConnect", attached_collision_objects=[object1])
184  if traj == None:
185  continue
186  print "Executing trajectory..."
187  if not velma.moveJointTraj(traj, start_time=0.5):
188  exitError(5)
189  if velma.waitForJoint() == 0:
190  break
191  else:
192  print "The trajectory could not be completed, retrying..."
193  continue
194 
195  rospy.sleep(0.5)
196  js = velma.getLastJointState()
197  if not isConfigurationClose(q_map_goal, js[1]):
198  exitError(6)
199 
200  rospy.sleep(1.0)
201 
202  q_map_end = {'torso_0_joint':0,
203  'right_arm_0_joint':-0.3,
204  'right_arm_1_joint':-1.8,
205  'right_arm_2_joint':1.25,
206  'right_arm_3_joint':0.85,
207  'right_arm_4_joint':0,
208  'right_arm_5_joint':-0.5,
209  'right_arm_6_joint':0,
210  'left_arm_0_joint':0.3,
211  'left_arm_1_joint':1.8,
212  'left_arm_2_joint':-1.25,
213  'left_arm_3_joint':-0.85,
214  'left_arm_4_joint':0,
215  'left_arm_5_joint':0.5,
216  'left_arm_6_joint':0
217  }
218 
219  print "Moving to starting position, using planned trajectory."
220  goal_constraint_2 = qMapToConstraints(q_map_end, 0.01, group=velma.getJointGroup("impedance_joints"))
221  for i in range(3):
222  rospy.sleep(0.5)
223  js = velma.getLastJointState()
224  print "Planning (try", i, ")..."
225  traj = p.plan(js[1], [goal_constraint_2], "impedance_joints", max_velocity_scaling_factor=0.15, planner_id="RRTConnect", attached_collision_objects=[object1])
226  if traj == None:
227  continue
228  print "Executing trajectory..."
229  if not velma.moveJointTraj(traj, start_time=0.5):
230  exitError(7)
231  if velma.waitForJoint() == 0:
232  break
233  else:
234  print "The trajectory could not be completed, retrying..."
235  continue
236  rospy.sleep(0.5)
237  js = velma.getLastJointState()
238  if not isConfigurationClose(q_map_end, js[1]):
239  exitError(8)
240 
241  pub.stop()
242 
243  exitError(0)
244 
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.