planning_scene_interface.py
Go to the documentation of this file.
1 # Software License Agreement (BSD License)
2 #
3 # Copyright (c) 2008, Willow Garage, Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions
8 # are met:
9 #
10 # * Redistributions of source code must retain the above copyright
11 # notice, this list of conditions and the following disclaimer.
12 # * Redistributions in binary form must reproduce the above
13 # copyright notice, this list of conditions and the following
14 # disclaimer in the documentation and/or other materials provided
15 # with the distribution.
16 # * Neither the name of Willow Garage, Inc. nor the names of its
17 # contributors may be used to endorse or promote products derived
18 # from this software without specific prior written permission.
19 #
20 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 # POSSIBILITY OF SUCH DAMAGE.
32 #
33 # Author: Ioan Sucan, Felix Messmer
34 
35 import rospy
36 from rosgraph.names import ns_join
37 from . import conversions
38 
39 from moveit_msgs.msg import PlanningScene, CollisionObject, AttachedCollisionObject
40 from moveit_msgs.msg import AllowedCollisionMatrix, AllowedCollisionEntry
41 from moveit_ros_planning_interface import _moveit_planning_scene_interface
42 from geometry_msgs.msg import Pose, Point
43 from shape_msgs.msg import SolidPrimitive, Plane, Mesh, MeshTriangle
44 from .exception import MoveItCommanderException
45 from moveit_msgs.srv import ApplyPlanningScene, ApplyPlanningSceneRequest
46 
47 try:
48  from pyassimp import pyassimp
49 except:
50  # support pyassimp > 3.0
51  try:
52  import pyassimp
53  except:
54  pyassimp = False
55  print(
56  "Failed to import pyassimp, see https://github.com/moveit/moveit/issues/86 for more info"
57  )
58 
59 
60 class PlanningSceneInterface(object):
61  """
62  Python interface for a C++ PlanningSceneInterface.
63  Uses both C++ wrapped methods and scene manipulation topics
64  to manipulate the PlanningScene managed by the PlanningSceneMonitor.
65  See wrap_python_planning_scene_interface.cpp for the wrapped methods.
66  """
67 
68  def __init__(self, ns="", synchronous=True):
69  self._psi = _moveit_planning_scene_interface.PlanningSceneInterface(ns)
70  self.__synchronous = synchronous
71 
72  if not self.__synchronous:
73  self._pub_co = rospy.Publisher(
74  ns_join(ns, "collision_object"), CollisionObject, queue_size=100
75  )
76  self._pub_aco = rospy.Publisher(
77  ns_join(ns, "attached_collision_object"),
78  AttachedCollisionObject,
79  queue_size=100,
80  )
81 
82  def __submit(self, collision_object, attach=False):
83  if self.__synchronous:
84  scene = PlanningScene()
85  scene.is_diff = True
86  scene.robot_state.is_diff = True
87  if attach:
88  scene.robot_state.attached_collision_objects = [collision_object]
89  else:
90  scene.world.collision_objects = [collision_object]
91  self._psi.apply_planning_scene(conversions.msg_to_string(scene))
92  else:
93  if attach:
94  self._pub_aco.publish(collision_object)
95  else:
96  self._pub_co.publish(collision_object)
97 
98  def add_object(self, collision_object):
99  """Add an object to the planning scene"""
100  self.__submit(collision_object, attach=False)
101 
102  def add_sphere(self, name, pose, radius=1):
103  """Add a sphere to the planning scene"""
104  co = self.make_sphere(name, pose, radius)
105  self.__submit(co, attach=False)
106 
107  def add_cylinder(self, name, pose, height, radius):
108  """Add a cylinder to the planning scene"""
109  co = self.make_cylinder(name, pose, height, radius)
110  self.__submit(co, attach=False)
111 
112  def add_cone(self, name, pose, height, radius):
113  """Add a cylinder to the planning scene"""
114  co = self.make_cone(name, pose, height, radius)
115  self.__submit(co, attach=False)
116 
117  def add_mesh(self, name, pose, filename, size=(1, 1, 1)):
118  """Add a mesh to the planning scene"""
119  co = self.make_mesh(name, pose, filename, size)
120  self.__submit(co, attach=False)
121 
122  def add_box(self, name, pose, size=(1, 1, 1)):
123  """Add a box to the planning scene"""
124  co = self.make_box(name, pose, size)
125  self.__submit(co, attach=False)
126 
127  def add_plane(self, name, pose, normal=(0, 0, 1), offset=0):
128  """Add a plane to the planning scene"""
129  co = self.make_plane(name, pose, normal, offset)
130  self.__submit(co, attach=False)
131 
132  def attach_object(self, object, link=None, touch_links=None):
133  """Attach an object to the given link"""
134  if isinstance(object, str):
135  object = self.__make_existing(object)
136  if isinstance(object, CollisionObject):
137  object = AttachedCollisionObject(object=object)
138 
139  if link is not None:
140  object.link_name = link
141  object.touch_links = (
142  touch_links if touch_links is not None else [object.link_name]
143  )
144 
145  self.__submit(object, attach=True)
146 
148  self, link, name, pose=None, filename="", size=(1, 1, 1), touch_links=None
149  ):
150  """Create mesh and attach it to the given link"""
151  if (pose is not None) and filename:
152  co = self.make_mesh(name, pose, filename, size)
153  else:
154  co = self.__make_existing(name)
155  self.attach_object(co, link, touch_links)
156 
157  def attach_box(self, link, name, pose=None, size=(1, 1, 1), touch_links=None):
158  """Create box and attach it to the given link"""
159  if pose is not None:
160  co = self.make_box(name, pose, size)
161  else:
162  co = self.__make_existing(name)
163  self.attach_object(co, link, touch_links)
164 
165  def attach_sphere(self, link, name, pose=None, radius=1, touch_links=None):
166  """Create sphere and attach it to the given link"""
167  if pose is not None:
168  co = self.make_sphere(name, pose, radius)
169  else:
170  co = self.__make_existing(name)
171  self.attach_object(co, link, touch_links)
172 
174  self, link, name, pose=None, height=1, radius=1, touch_links=None
175  ):
176  """Create cylinder and attach it to the given link"""
177  if pose is not None:
178  co = self.make_cylinder(name, pose, height, radius)
179  else:
180  co = self.__make_existing(name)
181  self.attach_object(co, link, touch_links)
182 
183  def clear(self):
184  """Remove all objects from the planning scene"""
185  self._psi.clear()
186 
187  def remove_world_object(self, name=None):
188  """
189  Remove an object from planning scene, or all if no name is provided
190  """
191  co = CollisionObject()
192  co.operation = CollisionObject.REMOVE
193  if name is not None:
194  co.id = name
195  self.__submit(co, attach=False)
196 
197  def remove_attached_object(self, link=None, name=None):
198  """
199  Remove an attached object from the robot, or all objects attached to the link if no name is provided,
200  or all attached objects in the scene if neither link nor name are provided.
201 
202  Removed attached objects remain in the scene as world objects.
203  Call remove_world_object afterwards to remove them from the scene.
204  """
205  aco = AttachedCollisionObject()
206  aco.object.operation = CollisionObject.REMOVE
207  if link is not None:
208  aco.link_name = link
209  if name is not None:
210  aco.object.id = name
211  self.__submit(aco, attach=True)
212 
213  def get_known_object_names(self, with_type=False):
214  """
215  Get the names of all known objects in the world. If with_type is set to true, only return objects that have a known type.
216  """
217  return self._psi.get_known_object_names(with_type)
218 
220  self, minx, miny, minz, maxx, maxy, maxz, with_type=False
221  ):
222  """
223  Get the names of known objects in the world that are located within a bounding region (specified in the frame reported by
224  get_planning_frame()). If with_type is set to true, only return objects that have a known type.
225  """
227  minx, miny, minz, maxx, maxy, maxz, with_type
228  )
229 
230  def get_object_poses(self, object_ids):
231  """
232  Get the poses from the objects identified by the given object ids list.
233  """
234  ser_ops = self._psi.get_object_poses(object_ids)
235  ops = dict()
236  for key in ser_ops:
237  msg = Pose()
238  conversions.msg_from_string(msg, ser_ops[key])
239  ops[key] = msg
240  return ops
241 
242  def get_objects(self, object_ids=[]):
243  """
244  Get the objects identified by the given object ids list. If no ids are provided, return all the known objects.
245  """
246  ser_objs = self._psi.get_objects(object_ids)
247  objs = dict()
248  for key in ser_objs:
249  msg = CollisionObject()
250  conversions.msg_from_string(msg, ser_objs[key])
251  objs[key] = msg
252  return objs
253 
254  def get_attached_objects(self, object_ids=[]):
255  """
256  Get the attached objects identified by the given object ids list. If no ids are provided, return all the attached objects.
257  """
258  ser_aobjs = self._psi.get_attached_objects(object_ids)
259  aobjs = dict()
260  for key in ser_aobjs:
261  msg = AttachedCollisionObject()
262  conversions.msg_from_string(msg, ser_aobjs[key])
263  aobjs[key] = msg
264  return aobjs
265 
266  def get_planning_scene(self, components):
267  """Get move_group's current planning scene"""
268  msg = PlanningScene()
269  conversions.msg_from_string(msg, self._psi.get_planning_scene(components))
270  return msg
271 
272  def apply_planning_scene(self, planning_scene_message):
273  """
274  Applies the planning scene message.
275  """
276  return self._psi.apply_planning_scene(
277  conversions.msg_to_string(planning_scene_message)
278  )
279 
280  @staticmethod
281  def __make_existing(name):
282  """
283  Create an empty Collision Object. Used when the object already exists
284  """
285  co = CollisionObject()
286  co.id = name
287  return co
288 
289  @staticmethod
290  def __make_primitive(name, pose, type, shape_args):
291  co = CollisionObject()
292  co.operation = CollisionObject.ADD
293  co.id = name
294  co.header = pose.header
295  co.pose = pose.pose
296  shape = SolidPrimitive()
297  shape.type = type
298  shape.dimensions = list(shape_args)
299  co.primitives = [shape]
300  return co
301 
302  @staticmethod
303  def make_box(name, pose, size):
304  return PlanningSceneInterface.__make_primitive(
305  name, pose, SolidPrimitive.BOX, size
306  )
307 
308  @staticmethod
309  def make_mesh(name, pose, filename, scale=(1, 1, 1)):
310  co = CollisionObject()
311  if pyassimp is False:
313  "Pyassimp needs patch https://launchpadlibrarian.net/319496602/patchPyassim.txt"
314  )
315  scene = pyassimp.load(filename)
316  if not scene.meshes or len(scene.meshes) == 0:
317  raise MoveItCommanderException("There are no meshes in the file")
318  if len(scene.meshes[0].faces) == 0:
319  raise MoveItCommanderException("There are no faces in the mesh")
320  co.operation = CollisionObject.ADD
321  co.id = name
322  co.header = pose.header
323  co.pose = pose.pose
324 
325  mesh = Mesh()
326  first_face = scene.meshes[0].faces[0]
327  if hasattr(first_face, "__len__"):
328  for face in scene.meshes[0].faces:
329  if len(face) == 3:
330  triangle = MeshTriangle()
331  triangle.vertex_indices = [face[0], face[1], face[2]]
332  mesh.triangles.append(triangle)
333  elif hasattr(first_face, "indices"):
334  for face in scene.meshes[0].faces:
335  if len(face.indices) == 3:
336  triangle = MeshTriangle()
337  triangle.vertex_indices = [
338  face.indices[0],
339  face.indices[1],
340  face.indices[2],
341  ]
342  mesh.triangles.append(triangle)
343  else:
345  "Unable to build triangles from mesh due to mesh object structure"
346  )
347  for vertex in scene.meshes[0].vertices:
348  point = Point()
349  point.x = vertex[0] * scale[0]
350  point.y = vertex[1] * scale[1]
351  point.z = vertex[2] * scale[2]
352  mesh.vertices.append(point)
353  co.meshes = [mesh]
354  pyassimp.release(scene)
355  return co
356 
357  @staticmethod
358  def make_sphere(name, pose, radius):
359  return PlanningSceneInterface.__make_primitive(
360  name, pose, SolidPrimitive.SPHERE, [radius]
361  )
362 
363  @staticmethod
364  def make_cylinder(name, pose, height, radius):
365  return PlanningSceneInterface.__make_primitive(
366  name, pose, SolidPrimitive.CYLINDER, [height, radius]
367  )
368 
369  @staticmethod
370  def make_cone(name, pose, height, radius):
371  return PlanningSceneInterface.__make_primitive(
372  name, pose, SolidPrimitive.CONE, [height, radius]
373  )
374 
375  def make_plane(self, name, pose, normal=(0, 0, 1), offset=0):
376  co = CollisionObject()
377  co.operation = CollisionObject.ADD
378  co.id = name
379  co.header = pose.header
380  p = Plane()
381  p.coef = list(normal)
382  p.coef.append(offset)
383  co.planes = [p]
384  co.plane_poses = [pose.pose]
385  return co
386 
387 
388 def acm_set_default(acm, obj, allow):
389  """Set default collision behavior for obj"""
390  if obj not in acm.default_entry_names:
391  acm.default_entry_names.append(obj)
392  acm.default_entry_values.append(allow)
393  else:
394  idx = acm.default_entry_names.index(obj)
395  acm.default_entry_values[idx] = allow
396 
397 
398 def acm_set_allowed(acm, obj, other=None, allow=True):
399  """Allow collisions between obj and other"""
400  if other is None:
401  acm.set_default(obj, allow)
402  return
403 
404  other_idx = acm.entry_names.index(other)
405  if obj not in acm.entry_names:
406  acm.entry_names.append(obj)
407  for entry in acm.entry_values:
408  entry.enabled.append(allow)
409  acm.entry_values.append(
410  AllowedCollisionEntry(enabled=[allow for i in range(len(acm.entry_names))])
411  )
412  acm.entry_values[-1].enabled[other_idx] = allow
413  else:
414  obj_idx = acm.entry_names.index(obj)
415  acm.entry_values[obj_idx].enabled[other_idx] = allow
416  acm.entry_values[other_idx].enabled[obj_idx] = allow
417 
418 
419 AllowedCollisionMatrix.set_default = acm_set_default
420 AllowedCollisionMatrix.set_allowed = acm_set_allowed
moveit_commander.planning_scene_interface.PlanningSceneInterface.__init__
def __init__(self, ns="", synchronous=True)
Definition: planning_scene_interface.py:68
moveit_commander.planning_scene_interface.PlanningSceneInterface.clear
def clear(self)
Definition: planning_scene_interface.py:183
moveit_commander.planning_scene_interface.PlanningSceneInterface.attach_cylinder
def attach_cylinder(self, link, name, pose=None, height=1, radius=1, touch_links=None)
Definition: planning_scene_interface.py:173
moveit_commander.planning_scene_interface.PlanningSceneInterface.make_cone
def make_cone(name, pose, height, radius)
Definition: planning_scene_interface.py:370
moveit_commander.planning_scene_interface.PlanningSceneInterface.remove_attached_object
def remove_attached_object(self, link=None, name=None)
Definition: planning_scene_interface.py:197
moveit_commander.planning_scene_interface.PlanningSceneInterface.add_cone
def add_cone(self, name, pose, height, radius)
Definition: planning_scene_interface.py:112
moveit_commander.planning_scene_interface.PlanningSceneInterface.apply_planning_scene
def apply_planning_scene(self, planning_scene_message)
Definition: planning_scene_interface.py:272
moveit_commander.planning_scene_interface.PlanningSceneInterface.get_planning_scene
def get_planning_scene(self, components)
Definition: planning_scene_interface.py:266
moveit_commander.planning_scene_interface.PlanningSceneInterface.make_cylinder
def make_cylinder(name, pose, height, radius)
Definition: planning_scene_interface.py:364
moveit_commander.planning_scene_interface.PlanningSceneInterface._pub_aco
_pub_aco
Definition: planning_scene_interface.py:76
moveit_commander.planning_scene_interface.PlanningSceneInterface.__submit
def __submit(self, collision_object, attach=False)
Definition: planning_scene_interface.py:82
moveit_commander.planning_scene_interface.PlanningSceneInterface.add_mesh
def add_mesh(self, name, pose, filename, size=(1, 1, 1))
Definition: planning_scene_interface.py:117
moveit_commander.planning_scene_interface.PlanningSceneInterface.add_box
def add_box(self, name, pose, size=(1, 1, 1))
Definition: planning_scene_interface.py:122
moveit_commander.planning_scene_interface.PlanningSceneInterface.__make_existing
def __make_existing(name)
Definition: planning_scene_interface.py:281
moveit_commander.planning_scene_interface.PlanningSceneInterface.get_known_object_names
def get_known_object_names(self, with_type=False)
Definition: planning_scene_interface.py:213
moveit_commander.planning_scene_interface.PlanningSceneInterface.add_object
def add_object(self, collision_object)
Definition: planning_scene_interface.py:98
moveit_commander.planning_scene_interface.PlanningSceneInterface.get_object_poses
def get_object_poses(self, object_ids)
Definition: planning_scene_interface.py:230
moveit_commander.planning_scene_interface.PlanningSceneInterface.__make_primitive
def __make_primitive(name, pose, type, shape_args)
Definition: planning_scene_interface.py:290
moveit_commander.planning_scene_interface.acm_set_default
def acm_set_default(acm, obj, allow)
Definition: planning_scene_interface.py:388
moveit_commander.exception.MoveItCommanderException
Definition: exception.py:36
moveit_commander.planning_scene_interface.PlanningSceneInterface.__synchronous
__synchronous
Definition: planning_scene_interface.py:70
moveit_commander.planning_scene_interface.PlanningSceneInterface.add_plane
def add_plane(self, name, pose, normal=(0, 0, 1), offset=0)
Definition: planning_scene_interface.py:127
moveit_commander.planning_scene_interface.acm_set_allowed
def acm_set_allowed(acm, obj, other=None, allow=True)
Definition: planning_scene_interface.py:398
moveit_commander.planning_scene_interface.PlanningSceneInterface.attach_box
def attach_box(self, link, name, pose=None, size=(1, 1, 1), touch_links=None)
Definition: planning_scene_interface.py:157
moveit_commander.planning_scene_interface.PlanningSceneInterface._psi
_psi
Definition: planning_scene_interface.py:69
moveit_commander.planning_scene_interface.PlanningSceneInterface.attach_object
def attach_object(self, object, link=None, touch_links=None)
Definition: planning_scene_interface.py:132
moveit_commander.planning_scene_interface.PlanningSceneInterface.make_mesh
def make_mesh(name, pose, filename, scale=(1, 1, 1))
Definition: planning_scene_interface.py:309
moveit_commander.planning_scene_interface.PlanningSceneInterface.remove_world_object
def remove_world_object(self, name=None)
Definition: planning_scene_interface.py:187
moveit_commander.planning_scene_interface.PlanningSceneInterface.attach_sphere
def attach_sphere(self, link, name, pose=None, radius=1, touch_links=None)
Definition: planning_scene_interface.py:165
moveit_commander.planning_scene_interface.PlanningSceneInterface.add_sphere
def add_sphere(self, name, pose, radius=1)
Definition: planning_scene_interface.py:102
moveit_commander.planning_scene_interface.PlanningSceneInterface.make_box
def make_box(name, pose, size)
Definition: planning_scene_interface.py:303
moveit_commander.planning_scene_interface.PlanningSceneInterface.attach_mesh
def attach_mesh(self, link, name, pose=None, filename="", size=(1, 1, 1), touch_links=None)
Definition: planning_scene_interface.py:147
moveit_commander.planning_scene_interface.PlanningSceneInterface.make_sphere
def make_sphere(name, pose, radius)
Definition: planning_scene_interface.py:358
moveit_commander.planning_scene_interface.PlanningSceneInterface.make_plane
def make_plane(self, name, pose, normal=(0, 0, 1), offset=0)
Definition: planning_scene_interface.py:375
moveit_commander.planning_scene_interface.PlanningSceneInterface._pub_co
_pub_co
Definition: planning_scene_interface.py:73
moveit_commander.planning_scene_interface.PlanningSceneInterface.get_known_object_names_in_roi
def get_known_object_names_in_roi(self, minx, miny, minz, maxx, maxy, maxz, with_type=False)
Definition: planning_scene_interface.py:219
moveit_commander.planning_scene_interface.PlanningSceneInterface.get_objects
def get_objects(self, object_ids=[])
Definition: planning_scene_interface.py:242
moveit_commander.planning_scene_interface.PlanningSceneInterface
Definition: planning_scene_interface.py:60
moveit_commander.planning_scene_interface.PlanningSceneInterface.get_attached_objects
def get_attached_objects(self, object_ids=[])
Definition: planning_scene_interface.py:254
moveit_commander.planning_scene_interface.PlanningSceneInterface.add_cylinder
def add_cylinder(self, name, pose, height, radius)
Definition: planning_scene_interface.py:107


moveit_commander
Author(s): Ioan Sucan
autogenerated on Thu Nov 21 2024 03:25:17