planning_scene_interface.py
Go to the documentation of this file.
00001 # Copyright 2011-2014, Michael Ferguson
00002 # All rights reserved.
00003 #
00004 # Redistribution and use in source and binary forms, with or without
00005 # modification, are permitted provided that the following conditions
00006 # are met:
00007 #
00008 #  * Redistributions of source code must retain the above copyright
00009 #    notice, this list of conditions and the following disclaimer.
00010 #  * Redistributions in binary form must reproduce the above
00011 #    copyright notice, this list of conditions and the following
00012 #    disclaimer in the documentation and/or other materials provided
00013 #    with the distribution.
00014 #
00015 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00016 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00017 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00018 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00019 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00020 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00021 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00023 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00024 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00025 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00026 # POSSIBILITY OF SUCH DAMAGE.
00027 
00028 import thread, copy
00029 import rospy
00030 
00031 try:
00032     from pyassimp import pyassimp
00033     use_pyassimp = True
00034 except:
00035     # In 16.04, pyassimp is busted
00036     # https://bugs.launchpad.net/ubuntu/+source/assimp/+bug/1589949
00037     use_pyassimp = False
00038 
00039 from geometry_msgs.msg import Pose, PoseStamped, Point
00040 from moveit_msgs.msg import CollisionObject, AttachedCollisionObject
00041 from moveit_msgs.msg import PlanningScene, PlanningSceneComponents, ObjectColor
00042 from moveit_msgs.srv import GetPlanningScene, ApplyPlanningScene
00043 from shape_msgs.msg import MeshTriangle, Mesh, SolidPrimitive, Plane
00044 
00045 ## @brief A class for managing the state of the planning scene
00046 ## @param frame The fixed frame in which planning is being done (needs to be part of robot?)
00047 ## @param ns A namespace to push all topics down into.
00048 ## @param init_from_service Whether to initialize our list of objects by calling the service
00049 ##            NOTE: this requires that said service be in the move_group launch file, which
00050 ##            is not the default from the setup assistant.
00051 class PlanningSceneInterface(object):
00052     def __init__(self, frame, ns='', init_from_service=True):
00053         # ns must be a string
00054         if not isinstance(ns, basestring):
00055             rospy.logerr('Namespace must be a string!')
00056             ns = ''
00057         elif not ns.endswith('/'):
00058             ns += '/'
00059 
00060         self._fixed_frame = frame
00061 
00062         self._scene_pub = rospy.Publisher(ns + 'planning_scene',
00063                                           PlanningScene,
00064                                           queue_size=10)
00065         self._apply_service = rospy.ServiceProxy(ns + 'apply_planning_scene', ApplyPlanningScene)
00066         # track the attached and collision objects
00067         self._mutex = thread.allocate_lock()
00068         # these are updated based what the planning scene actually contains
00069         self._attached = list()
00070         self._collision = list()
00071         # these are updated based on internal state
00072         self._objects = dict()
00073         self._attached_objects = dict()
00074         self._removed = dict()
00075         self._attached_removed = dict()
00076         self._colors = dict()
00077 
00078         # get the initial planning scene
00079         if init_from_service:
00080             rospy.loginfo('Waiting for get_planning_scene')
00081             rospy.wait_for_service(ns + 'get_planning_scene')
00082             self._service = rospy.ServiceProxy(ns + 'get_planning_scene',
00083                                                GetPlanningScene)
00084             try:
00085                 req = PlanningSceneComponents()
00086                 req.components = sum([
00087                     PlanningSceneComponents.WORLD_OBJECT_NAMES,
00088                     PlanningSceneComponents.WORLD_OBJECT_GEOMETRY,
00089                     PlanningSceneComponents.ROBOT_STATE_ATTACHED_OBJECTS])
00090                 scene = self._service(req)
00091                 self.sceneCb(scene.scene, initial=True)
00092             except rospy.ServiceException as e:
00093                 rospy.logerr('Failed to get initial planning scene, results may be wonky: %s', e)
00094 
00095         # subscribe to planning scene
00096         rospy.Subscriber(ns + 'move_group/monitored_planning_scene',
00097                          PlanningScene,
00098                          self.sceneCb)
00099 
00100     ## @brief Send new update to planning scene
00101     ## @param collision_object A collision object to add to scene, or None
00102     ## @param attached_collision_object Attached collision object to add to scene, or None
00103     ## @param use_service If true, update will be sent via apply service, otherwise by topic
00104     def sendUpdate(self, collision_object, attached_collision_object, use_service=True):
00105         ps = PlanningScene()
00106         ps.is_diff = True
00107         if collision_object:
00108             ps.world.collision_objects.append(collision_object)
00109 
00110         if attached_collision_object:
00111             ps.robot_state.attached_collision_objects.append(attached_collision_object)
00112 
00113         if use_service:
00114             resp = self._apply_service.call(ps)
00115             if not resp.success:
00116                 rospy.logerr("Could not apply planning scene diff.")
00117         else:
00118             self._scene_pub.publish(ps)
00119 
00120     ## @brief Clear the planning scene of all objects
00121     def clear(self):
00122         for name in self.getKnownCollisionObjects():
00123             self.removeCollisionObject(name, True)
00124         for name in self.getKnownAttachedObjects():
00125             self.removeAttachedObject(name, True)
00126         self.waitForSync()
00127 
00128     ## @brief Make a mesh collision object
00129     ## @param name Name of the object
00130     ## @param pose A geometry_msgs/Pose for the object
00131     ## @param filename The mesh file to load
00132     def makeMesh(self, name, pose, filename):
00133         if not use_pyassimp:
00134             rospy.logerr('pyassimp is broken on your platform, cannot load meshes')
00135             return
00136         scene = pyassimp.load(filename)
00137         if not scene.meshes:
00138             rospy.logerr('Unable to load mesh')
00139             return
00140 
00141         mesh = Mesh()
00142         for face in scene.meshes[0].faces:
00143             triangle = MeshTriangle()
00144             if len(face.indices) == 3:
00145                 triangle.vertex_indices = [face.indices[0],
00146                                            face.indices[1],
00147                                            face.indices[2]]
00148             mesh.triangles.append(triangle)
00149         for vertex in scene.meshes[0].vertices:
00150             point = Point()
00151             point.x = vertex[0]
00152             point.y = vertex[1]
00153             point.z = vertex[2]
00154             mesh.vertices.append(point)
00155         pyassimp.release(scene)
00156 
00157         o = CollisionObject()
00158         o.header.stamp = rospy.Time.now()
00159         o.header.frame_id = self._fixed_frame
00160         o.id = name
00161         o.meshes.append(mesh)
00162         o.mesh_poses.append(pose)
00163         o.operation = o.ADD
00164         return o
00165 
00166     ## @brief Make a solid primitive collision object
00167     ## @param name Name of the object
00168     ## @param solid The solid primitive to add
00169     ## @param pose A geometry_msgs/Pose for the object
00170     def makeSolidPrimitive(self, name, solid, pose):
00171         o = CollisionObject()
00172         o.header.stamp = rospy.Time.now()
00173         o.header.frame_id = self._fixed_frame
00174         o.id = name
00175         o.primitives.append(solid)
00176         o.primitive_poses.append(pose)
00177         o.operation = o.ADD
00178         return o
00179 
00180     ## @brief Make an attachedCollisionObject
00181     def makeAttached(self, link_name, obj, touch_links, detach_posture,
00182                      weight):
00183         o = AttachedCollisionObject()
00184         o.link_name = link_name
00185         o.object = obj
00186         if touch_links:
00187             o.touch_links = touch_links
00188         if detach_posture:
00189             o.detach_posture = detach_posture
00190         o.weight = weight
00191         return o
00192 
00193     ## @brief Insert a mesh into the planning scene
00194     ## @param name Name of the object
00195     ## @param pose A geometry_msgs/Pose for the object
00196     ## @param filename The mesh file to load
00197     ## @param use_service If true, update will be sent via apply service
00198     def addMesh(self, name, pose, filename, use_service=True):
00199         o = self.makeMesh(name, pose, filename)
00200         self._objects[name] = o
00201         self.sendUpdate(o, None, use_service)
00202 
00203     ## @brief Attach a mesh into the planning scene
00204     ## @param name Name of the object
00205     ## @param pose A geometry_msgs/Pose for the object
00206     ## @param filename The mesh file to load
00207     ## @param use_service If true, update will be sent via apply service
00208     def attachMesh(self, name, pose, filename, link_name, touch_links=None,
00209                    detach_posture=None, weight=0.0, use_service=True):
00210         o = self.makeMesh(name, pose, filename)
00211         o.header.frame_id = link_name
00212         a = self.makeAttached(link_name, o, touch_links, detach_posture,
00213                               weight)
00214         self._attached_objects[name] = a
00215         self.sendUpdate(None, a, use_service)
00216 
00217     ## @brief Insert a solid primitive into planning scene
00218     ## @param use_service If true, update will be sent via apply service
00219     def addSolidPrimitive(self, name, solid, pose, use_service=True):
00220         o = self.makeSolidPrimitive(name, solid, pose)
00221         self._objects[name] = o
00222         self.sendUpdate(o, None, use_service)
00223 
00224     ## @brief Insert new cylinder into planning scene
00225     ## @param use_service If true, update will be sent via apply service
00226     def addCylinder(self, name, height, radius, x, y, z, use_service=True):
00227         s = SolidPrimitive()
00228         s.dimensions = [height, radius]
00229         s.type = s.CYLINDER
00230 
00231         ps = PoseStamped()
00232         ps.header.frame_id = self._fixed_frame
00233         ps.pose.position.x = x
00234         ps.pose.position.y = y
00235         ps.pose.position.z = z
00236         ps.pose.orientation.w = 1.0
00237 
00238         self.addSolidPrimitive(name, s, ps.pose, use_service)
00239 
00240     ## @brief Insert new box into planning scene
00241     ## @param name Name of the object
00242     ## @param size_x The x-dimensions size of the box
00243     ## @param size_y The y-dimensions size of the box
00244     ## @param size_z The z-dimensions size of the box
00245     ## @param x The x position in link_name frame
00246     ## @param y The y position in link_name frame
00247     ## @param z The z position in link_name frame
00248     ## @param use_service If true, update will be sent via apply service
00249     def addBox(self, name, size_x, size_y, size_z, x, y, z, use_service=True):
00250         s = SolidPrimitive()
00251         s.dimensions = [size_x, size_y, size_z]
00252         s.type = s.BOX
00253 
00254         ps = PoseStamped()
00255         ps.header.frame_id = self._fixed_frame
00256         ps.pose.position.x = x
00257         ps.pose.position.y = y
00258         ps.pose.position.z = z
00259         ps.pose.orientation.w = 1.0
00260 
00261         self.addSolidPrimitive(name, s, ps.pose, use_service)
00262 
00263     ## @brief Attach a box into the planning scene
00264     ## @param name Name of the object
00265     ## @param size_x The x-dimensions size of the box
00266     ## @param size_y The y-dimensions size of the box
00267     ## @param size_z The z-dimensions size of the box
00268     ## @param x The x position in link_name frame
00269     ## @param y The y position in link_name frame
00270     ## @param z The z position in link_name frame
00271     ## @param link_name Name of link to attach this object to
00272     ## @param touch_links Names of robot links that can touch this object
00273     ## @param use_service If true, update will be sent via apply service
00274     def attachBox(self, name, size_x, size_y, size_z, x, y, z, link_name,
00275                   touch_links=None, detach_posture=None, weight=0.0,
00276                   use_service=True):
00277         s = SolidPrimitive()
00278         s.dimensions = [size_x, size_y, size_z]
00279         s.type = s.BOX
00280 
00281         p = Pose()
00282         p.position.x = x
00283         p.position.y = y
00284         p.position.z = z
00285         p.orientation.w = 1.0
00286         o = self.makeSolidPrimitive(name, s, p)
00287         o.header.frame_id = link_name
00288         a = self.makeAttached(link_name, o, touch_links, detach_posture, weight)
00289         self._attached_objects[name] = a
00290         self.sendUpdate(None, a, use_service)
00291 
00292     ## @brief Insert new cube to planning scene
00293     ## @param use_service If true, update will be sent via apply service
00294     def addCube(self, name, size, x, y, z, use_service=True):
00295         self.addBox(name, size, size, size, x, y, z, use_service)
00296 
00297     ## @brief Send message to remove object
00298     ## @param use_service If true, update will be sent via apply service
00299     def removeCollisionObject(self, name, use_service=True):
00300         """ Remove an object. """
00301         o = CollisionObject()
00302         o.header.stamp = rospy.Time.now()
00303         o.header.frame_id = self._fixed_frame
00304         o.id = name
00305         o.operation = o.REMOVE
00306 
00307         try:
00308             del self._objects[name]
00309             self._removed[name] = o
00310         except KeyError:
00311             pass
00312 
00313         self.sendUpdate(o, None, use_service)
00314 
00315     ## @brief Send message to remove object
00316     ## @param use_service If true, update will be sent via apply service
00317     def removeAttachedObject(self, name, use_service=True):
00318         """ Remove an attached object. """
00319         o = AttachedCollisionObject()
00320         o.object.operation = CollisionObject.REMOVE
00321         o.object.id = name
00322 
00323         try:
00324             del self._attached_objects[name]
00325             self._attached_removed[name] = o
00326         except KeyError:
00327             pass
00328 
00329         self.sendUpdate(None, o, use_service)
00330 
00331     ## @brief Update the object lists from a PlanningScene message
00332     def sceneCb(self, msg, initial=False):
00333         """ Recieve updates from move_group. """
00334         self._mutex.acquire()
00335         for obj in msg.world.collision_objects:
00336             try:
00337                 if obj.operation == obj.ADD:
00338                     self._collision.append(obj.id)
00339                     rospy.logdebug('ObjectManager: Added Collision Obj "%s"',
00340                                    obj.id)
00341                     if initial:
00342                         # this is our initial planning scene, hold onto each object
00343                         self._objects[obj.id] = obj
00344                 elif obj.operation == obj.REMOVE:
00345                     self._collision.remove(obj.id)
00346                     self._removed.pop(obj.id, None)
00347                     rospy.logdebug('ObjectManager: Removed Collision Obj "%s"',
00348                                    obj.id)
00349             except ValueError:
00350                 pass
00351         self._attached = list()
00352         for obj in msg.robot_state.attached_collision_objects:
00353             rospy.logdebug('ObjectManager: attached collision Obj "%s"',
00354                            obj.object.id)
00355             self._attached.append(obj.object.id)
00356             if initial:
00357                 # this is our initial planning scene, hold onto each object
00358                 self._attached_objects[obj.object.id] = obj
00359         self._mutex.release()
00360 
00361     ## @brief Get a list of names of collision objects
00362     def getKnownCollisionObjects(self):
00363         self._mutex.acquire()
00364         l = copy.deepcopy(self._collision)
00365         self._mutex.release()
00366         return l
00367 
00368     ## @brief Get a list of names of attached objects
00369     def getKnownAttachedObjects(self):
00370         self._mutex.acquire()
00371         l = copy.deepcopy(self._attached)
00372         self._mutex.release()
00373         return l
00374 
00375     ## @brief Wait for sync
00376     def waitForSync(self, max_time=2.0):
00377         sync = False
00378         t = rospy.Time.now()
00379         while not sync:
00380             sync = True
00381             # delete objects that should be gone
00382             for name in self._collision:
00383                 if name in self._removed.keys():
00384                     # should be removed, is not
00385                     rospy.logwarn('ObjectManager: %s not removed yet', name)
00386                     self.removeCollisionObject(name, False)
00387                     sync = False
00388             for name in self._attached:
00389                 if name in self._attached_removed.keys():
00390                     # should be removed, is not
00391                     rospy.logwarn('ObjectManager: Attached object name: %s not removed yet', name)
00392                     self.removeAttachedObject(name, False)
00393                     sync = False
00394             # add missing objects
00395             for name in self._objects.keys():
00396                 if name not in self._collision + self._attached:
00397                     rospy.logwarn('ObjectManager: %s not added yet', name)
00398                     self.sendUpdate(self._objects[name], None, False)
00399                     sync = False
00400             for name in self._attached_objects.keys():
00401                 if name not in self._attached:
00402                     rospy.logwarn('ObjectManager: %s not attached yet', name)
00403                     self.sendUpdate(None, self._attached_objects[name], False)
00404                     sync = False
00405             # timeout
00406             if rospy.Time.now() - t > rospy.Duration(max_time):
00407                 rospy.logerr('ObjectManager: sync timed out.')
00408                 break
00409             rospy.logdebug('ObjectManager: waiting for sync.')
00410             rospy.sleep(0.1)
00411 
00412     ## @brief Set the color of an object
00413     def setColor(self, name, r, g, b, a=0.9):
00414         # Create our color
00415         color = ObjectColor()
00416         color.id = name
00417         color.color.r = r
00418         color.color.g = g
00419         color.color.b = b
00420         color.color.a = a
00421         self._colors[name] = color
00422 
00423     ## @brief Actually send the colors to MoveIt!
00424     def sendColors(self):
00425         # Need to send a planning scene diff
00426         p = PlanningScene()
00427         p.is_diff = True
00428         for color in self._colors.values():
00429             p.object_colors.append(color)
00430         resp = self._apply_service.call(p)
00431         if not resp.success:
00432             rospy.logerr("Could not update colors through service, using topic instead.")
00433             self._scene_pub.publish(p)


moveit_python
Author(s): Michael Ferguson
autogenerated on Sat Jun 8 2019 18:38:59