planning_scene_interface.py
Go to the documentation of this file.
1 # Copyright 2011-2014, Michael Ferguson
2 # All rights reserved.
3 #
4 # Redistribution and use in source and binary forms, with or without
5 # modification, are permitted provided that the following conditions
6 # are met:
7 #
8 # * Redistributions of source code must retain the above copyright
9 # notice, this list of conditions and the following disclaimer.
10 # * Redistributions in binary form must reproduce the above
11 # copyright notice, this list of conditions and the following
12 # disclaimer in the documentation and/or other materials provided
13 # with the distribution.
14 #
15 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
16 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
17 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
18 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
19 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
20 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
21 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
23 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
24 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
25 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26 # POSSIBILITY OF SUCH DAMAGE.
27 
28 import thread, copy
29 import rospy
30 
31 try:
32  from pyassimp import pyassimp
33  use_pyassimp = True
34 except:
35  # In 16.04, pyassimp is busted
36  # https://bugs.launchpad.net/ubuntu/+source/assimp/+bug/1589949
37  use_pyassimp = False
38 
39 from geometry_msgs.msg import Pose, PoseStamped, Point
40 from moveit_msgs.msg import CollisionObject, AttachedCollisionObject
41 from moveit_msgs.msg import PlanningScene, PlanningSceneComponents, ObjectColor
42 from moveit_msgs.srv import GetPlanningScene, ApplyPlanningScene
43 from shape_msgs.msg import MeshTriangle, Mesh, SolidPrimitive, Plane
44 
45 ## @brief A class for managing the state of the planning scene
46 ## @param frame The fixed frame in which planning is being done (needs to be part of robot?)
47 ## @param ns A namespace to push all topics down into.
48 ## @param init_from_service Whether to initialize our list of objects by calling the service
49 ## NOTE: this requires that said service be in the move_group launch file, which
50 ## is not the default from the setup assistant.
51 class PlanningSceneInterface(object):
52  def __init__(self, frame, ns='', init_from_service=True):
53  # ns must be a string
54  if not isinstance(ns, basestring):
55  rospy.logerr('Namespace must be a string!')
56  ns = ''
57  elif not ns.endswith('/'):
58  ns += '/'
59 
60  self._fixed_frame = frame
61 
62  self._scene_pub = rospy.Publisher(ns + 'planning_scene',
63  PlanningScene,
64  queue_size=10)
65  self._apply_service = rospy.ServiceProxy(ns + 'apply_planning_scene', ApplyPlanningScene)
66  # track the attached and collision objects
67  self._mutex = thread.allocate_lock()
68  # these are updated based what the planning scene actually contains
69  self._attached = list()
70  self._collision = list()
71  # these are updated based on internal state
72  self._objects = dict()
73  self._attached_objects = dict()
74  self._removed = dict()
75  self._attached_removed = dict()
76  self._colors = dict()
77 
78  # get the initial planning scene
79  if init_from_service:
80  rospy.loginfo('Waiting for get_planning_scene')
81  rospy.wait_for_service(ns + 'get_planning_scene')
82  self._service = rospy.ServiceProxy(ns + 'get_planning_scene',
83  GetPlanningScene)
84  try:
85  req = PlanningSceneComponents()
86  req.components = sum([
87  PlanningSceneComponents.WORLD_OBJECT_NAMES,
88  PlanningSceneComponents.WORLD_OBJECT_GEOMETRY,
89  PlanningSceneComponents.ROBOT_STATE_ATTACHED_OBJECTS])
90  scene = self._service(req)
91  self.sceneCb(scene.scene, initial=True)
92  except rospy.ServiceException as e:
93  rospy.logerr('Failed to get initial planning scene, results may be wonky: %s', e)
94 
95  # subscribe to planning scene
96  rospy.Subscriber(ns + 'move_group/monitored_planning_scene',
97  PlanningScene,
98  self.sceneCb)
99 
100  ## @brief Send new update to planning scene
101  ## @param collision_object A collision object to add to scene, or None
102  ## @param attached_collision_object Attached collision object to add to scene, or None
103  ## @param use_service If true, update will be sent via apply service, otherwise by topic
104  def sendUpdate(self, collision_object, attached_collision_object, use_service=True):
105  ps = PlanningScene()
106  ps.is_diff = True
107  if collision_object:
108  ps.world.collision_objects.append(collision_object)
109 
110  if attached_collision_object:
111  ps.robot_state.attached_collision_objects.append(attached_collision_object)
112 
113  if use_service:
114  resp = self._apply_service.call(ps)
115  if not resp.success:
116  rospy.logerr("Could not apply planning scene diff.")
117  else:
118  self._scene_pub.publish(ps)
119 
120  ## @brief Clear the planning scene of all objects
121  def clear(self):
122  for name in self.getKnownCollisionObjects():
123  self.removeCollisionObject(name, True)
124  for name in self.getKnownAttachedObjects():
125  self.removeAttachedObject(name, True)
126  self.waitForSync()
127 
128  ## @brief Make a mesh collision object
129  ## @param name Name of the object
130  ## @param pose A geometry_msgs/Pose for the object
131  ## @param filename The mesh file to load
132  def makeMesh(self, name, pose, filename):
133  if not use_pyassimp:
134  rospy.logerr('pyassimp is broken on your platform, cannot load meshes')
135  return
136  scene = pyassimp.load(filename)
137  if not scene.meshes:
138  rospy.logerr('Unable to load mesh')
139  return
140 
141  mesh = Mesh()
142  for face in scene.meshes[0].faces:
143  triangle = MeshTriangle()
144  if len(face.indices) == 3:
145  triangle.vertex_indices = [face.indices[0],
146  face.indices[1],
147  face.indices[2]]
148  mesh.triangles.append(triangle)
149  for vertex in scene.meshes[0].vertices:
150  point = Point()
151  point.x = vertex[0]
152  point.y = vertex[1]
153  point.z = vertex[2]
154  mesh.vertices.append(point)
155  pyassimp.release(scene)
156 
157  o = CollisionObject()
158  o.header.stamp = rospy.Time.now()
159  o.header.frame_id = self._fixed_frame
160  o.id = name
161  o.meshes.append(mesh)
162  o.mesh_poses.append(pose)
163  o.operation = o.ADD
164  return o
165 
166  ## @brief Make a solid primitive collision object
167  ## @param name Name of the object
168  ## @param solid The solid primitive to add
169  ## @param pose A geometry_msgs/Pose for the object
170  def makeSolidPrimitive(self, name, solid, pose):
171  o = CollisionObject()
172  o.header.stamp = rospy.Time.now()
173  o.header.frame_id = self._fixed_frame
174  o.id = name
175  o.primitives.append(solid)
176  o.primitive_poses.append(pose)
177  o.operation = o.ADD
178  return o
179 
180  ## @brief Make an attachedCollisionObject
181  def makeAttached(self, link_name, obj, touch_links, detach_posture,
182  weight):
183  o = AttachedCollisionObject()
184  o.link_name = link_name
185  o.object = obj
186  if touch_links:
187  o.touch_links = touch_links
188  if detach_posture:
189  o.detach_posture = detach_posture
190  o.weight = weight
191  return o
192 
193  ## @brief Insert a mesh into the planning scene
194  ## @param name Name of the object
195  ## @param pose A geometry_msgs/Pose for the object
196  ## @param filename The mesh file to load
197  ## @param use_service If true, update will be sent via apply service
198  def addMesh(self, name, pose, filename, use_service=True):
199  o = self.makeMesh(name, pose, filename)
200  self._objects[name] = o
201  self.sendUpdate(o, None, use_service)
202 
203  ## @brief Attach a mesh into the planning scene
204  ## @param name Name of the object
205  ## @param pose A geometry_msgs/Pose for the object
206  ## @param filename The mesh file to load
207  ## @param use_service If true, update will be sent via apply service
208  def attachMesh(self, name, pose, filename, link_name, touch_links=None,
209  detach_posture=None, weight=0.0, use_service=True):
210  o = self.makeMesh(name, pose, filename)
211  o.header.frame_id = link_name
212  a = self.makeAttached(link_name, o, touch_links, detach_posture,
213  weight)
214  self._attached_objects[name] = a
215  self.sendUpdate(None, a, use_service)
216 
217  ## @brief Insert a solid primitive into planning scene
218  ## @param use_service If true, update will be sent via apply service
219  def addSolidPrimitive(self, name, solid, pose, use_service=True):
220  o = self.makeSolidPrimitive(name, solid, pose)
221  self._objects[name] = o
222  self.sendUpdate(o, None, use_service)
223 
224  ## @brief Insert new cylinder into planning scene
225  ## @param use_service If true, update will be sent via apply service
226  def addCylinder(self, name, height, radius, x, y, z, use_service=True):
227  s = SolidPrimitive()
228  s.dimensions = [height, radius]
229  s.type = s.CYLINDER
230 
231  ps = PoseStamped()
232  ps.header.frame_id = self._fixed_frame
233  ps.pose.position.x = x
234  ps.pose.position.y = y
235  ps.pose.position.z = z
236  ps.pose.orientation.w = 1.0
237 
238  self.addSolidPrimitive(name, s, ps.pose, use_service)
239 
240  ## @brief Insert new box into planning scene
241  ## @param name Name of the object
242  ## @param size_x The x-dimensions size of the box
243  ## @param size_y The y-dimensions size of the box
244  ## @param size_z The z-dimensions size of the box
245  ## @param x The x position in link_name frame
246  ## @param y The y position in link_name frame
247  ## @param z The z position in link_name frame
248  ## @param use_service If true, update will be sent via apply service
249  def addBox(self, name, size_x, size_y, size_z, x, y, z, use_service=True):
250  s = SolidPrimitive()
251  s.dimensions = [size_x, size_y, size_z]
252  s.type = s.BOX
253 
254  ps = PoseStamped()
255  ps.header.frame_id = self._fixed_frame
256  ps.pose.position.x = x
257  ps.pose.position.y = y
258  ps.pose.position.z = z
259  ps.pose.orientation.w = 1.0
260 
261  self.addSolidPrimitive(name, s, ps.pose, use_service)
262 
263  ## @brief Attach a box into the planning scene
264  ## @param name Name of the object
265  ## @param size_x The x-dimensions size of the box
266  ## @param size_y The y-dimensions size of the box
267  ## @param size_z The z-dimensions size of the box
268  ## @param x The x position in link_name frame
269  ## @param y The y position in link_name frame
270  ## @param z The z position in link_name frame
271  ## @param link_name Name of link to attach this object to
272  ## @param touch_links Names of robot links that can touch this object
273  ## @param use_service If true, update will be sent via apply service
274  def attachBox(self, name, size_x, size_y, size_z, x, y, z, link_name,
275  touch_links=None, detach_posture=None, weight=0.0,
276  use_service=True):
277  s = SolidPrimitive()
278  s.dimensions = [size_x, size_y, size_z]
279  s.type = s.BOX
280 
281  p = Pose()
282  p.position.x = x
283  p.position.y = y
284  p.position.z = z
285  p.orientation.w = 1.0
286  o = self.makeSolidPrimitive(name, s, p)
287  o.header.frame_id = link_name
288  a = self.makeAttached(link_name, o, touch_links, detach_posture, weight)
289  self._attached_objects[name] = a
290  self.sendUpdate(None, a, use_service)
291 
292  ## @brief Insert new cube to planning scene
293  ## @param use_service If true, update will be sent via apply service
294  def addCube(self, name, size, x, y, z, use_service=True):
295  self.addBox(name, size, size, size, x, y, z, use_service)
296 
297  ## @brief Send message to remove object
298  ## @param use_service If true, update will be sent via apply service
299  def removeCollisionObject(self, name, use_service=True):
300  """ Remove an object. """
301  o = CollisionObject()
302  o.header.stamp = rospy.Time.now()
303  o.header.frame_id = self._fixed_frame
304  o.id = name
305  o.operation = o.REMOVE
306 
307  try:
308  del self._objects[name]
309  self._removed[name] = o
310  except KeyError:
311  pass
312 
313  self.sendUpdate(o, None, use_service)
314 
315  ## @brief Send message to remove object
316  ## @param use_service If true, update will be sent via apply service
317  def removeAttachedObject(self, name, use_service=True):
318  """ Remove an attached object. """
319  o = AttachedCollisionObject()
320  o.object.operation = CollisionObject.REMOVE
321  o.object.id = name
322 
323  try:
324  del self._attached_objects[name]
325  self._attached_removed[name] = o
326  except KeyError:
327  pass
328 
329  self.sendUpdate(None, o, use_service)
330 
331  ## @brief Update the object lists from a PlanningScene message
332  def sceneCb(self, msg, initial=False):
333  """ Recieve updates from move_group. """
334  self._mutex.acquire()
335  for obj in msg.world.collision_objects:
336  try:
337  if obj.operation == obj.ADD:
338  self._collision.append(obj.id)
339  rospy.logdebug('ObjectManager: Added Collision Obj "%s"',
340  obj.id)
341  if initial:
342  # this is our initial planning scene, hold onto each object
343  self._objects[obj.id] = obj
344  elif obj.operation == obj.REMOVE:
345  self._collision.remove(obj.id)
346  self._removed.pop(obj.id, None)
347  rospy.logdebug('ObjectManager: Removed Collision Obj "%s"',
348  obj.id)
349  except ValueError:
350  pass
351  self._attached = list()
352  for obj in msg.robot_state.attached_collision_objects:
353  rospy.logdebug('ObjectManager: attached collision Obj "%s"',
354  obj.object.id)
355  self._attached.append(obj.object.id)
356  if initial:
357  # this is our initial planning scene, hold onto each object
358  self._attached_objects[obj.object.id] = obj
359  self._mutex.release()
360 
361  ## @brief Get a list of names of collision objects
363  self._mutex.acquire()
364  l = copy.deepcopy(self._collision)
365  self._mutex.release()
366  return l
367 
368  ## @brief Get a list of names of attached objects
370  self._mutex.acquire()
371  l = copy.deepcopy(self._attached)
372  self._mutex.release()
373  return l
374 
375  ## @brief Wait for sync
376  def waitForSync(self, max_time=2.0):
377  sync = False
378  t = rospy.Time.now()
379  while not sync:
380  sync = True
381  # delete objects that should be gone
382  for name in self._collision:
383  if name in self._removed.keys():
384  # should be removed, is not
385  rospy.logwarn('ObjectManager: %s not removed yet', name)
386  self.removeCollisionObject(name, False)
387  sync = False
388  for name in self._attached:
389  if name in self._attached_removed.keys():
390  # should be removed, is not
391  rospy.logwarn('ObjectManager: Attached object name: %s not removed yet', name)
392  self.removeAttachedObject(name, False)
393  sync = False
394  # add missing objects
395  for name in self._objects.keys():
396  if name not in self._collision + self._attached:
397  rospy.logwarn('ObjectManager: %s not added yet', name)
398  self.sendUpdate(self._objects[name], None, False)
399  sync = False
400  for name in self._attached_objects.keys():
401  if name not in self._attached:
402  rospy.logwarn('ObjectManager: %s not attached yet', name)
403  self.sendUpdate(None, self._attached_objects[name], False)
404  sync = False
405  # timeout
406  if rospy.Time.now() - t > rospy.Duration(max_time):
407  rospy.logerr('ObjectManager: sync timed out.')
408  break
409  rospy.logdebug('ObjectManager: waiting for sync.')
410  rospy.sleep(0.1)
411 
412  ## @brief Set the color of an object
413  def setColor(self, name, r, g, b, a=0.9):
414  # Create our color
415  color = ObjectColor()
416  color.id = name
417  color.color.r = r
418  color.color.g = g
419  color.color.b = b
420  color.color.a = a
421  self._colors[name] = color
422 
423  ## @brief Actually send the colors to MoveIt!
424  def sendColors(self):
425  # Need to send a planning scene diff
426  p = PlanningScene()
427  p.is_diff = True
428  for color in self._colors.values():
429  p.object_colors.append(color)
430  resp = self._apply_service.call(p)
431  if not resp.success:
432  rospy.logerr("Could not update colors through service, using topic instead.")
433  self._scene_pub.publish(p)
def sendUpdate(self, collision_object, attached_collision_object, use_service=True)
Send new update to planning scene.
def removeCollisionObject(self, name, use_service=True)
Send message to remove object.
def sceneCb(self, msg, initial=False)
Update the object lists from a PlanningScene message.
def getKnownCollisionObjects(self)
Get a list of names of collision objects.
def attachMesh(self, name, pose, filename, link_name, touch_links=None, detach_posture=None, weight=0.0, use_service=True)
Attach a mesh into the planning scene.
def addBox(self, name, size_x, size_y, size_z, x, y, z, use_service=True)
Insert new box into planning scene.
def addCylinder(self, name, height, radius, x, y, z, use_service=True)
Insert new cylinder into planning scene.
def clear(self)
Clear the planning scene of all objects.
def setColor(self, name, r, g, b, a=0.9)
Set the color of an object.
def getKnownAttachedObjects(self)
Get a list of names of attached objects.
def makeSolidPrimitive(self, name, solid, pose)
Make a solid primitive collision object.
def makeMesh(self, name, pose, filename)
Make a mesh collision object.
def attachBox(self, name, size_x, size_y, size_z, x, y, z, link_name, touch_links=None, detach_posture=None, weight=0.0, use_service=True)
Attach a box into the planning scene.
def addCube(self, name, size, x, y, z, use_service=True)
Insert new cube to planning scene.
def makeAttached(self, link_name, obj, touch_links, detach_posture, weight)
Make an attachedCollisionObject.
def addMesh(self, name, pose, filename, use_service=True)
Insert a mesh into the planning scene.
def addSolidPrimitive(self, name, solid, pose, use_service=True)
Insert a solid primitive into planning scene.
def __init__(self, frame, ns='', init_from_service=True)
A class for managing the state of the planning scene.
def removeAttachedObject(self, name, use_service=True)
Send message to remove object.


moveit_python
Author(s): Michael Ferguson
autogenerated on Wed Jun 5 2019 21:51:17