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
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 init_from_service Whether to initialize our list of objects by calling the service
00048 ##            NOTE: this requires that said service be in the move_group launch file, which
00049 ##            is not the default from the setup assistant.
00050 class PlanningSceneInterface(object):
00051     def __init__(self, frame, init_from_service=True):
00052         self._fixed_frame = frame
00053 
00054         # publisher to send objects to MoveIt
00055         self._pub = rospy.Publisher('collision_object',
00056                                     CollisionObject,
00057                                     queue_size=10)
00058         self._attached_pub = rospy.Publisher('attached_collision_object',
00059                                              AttachedCollisionObject,
00060                                              queue_size=10)
00061         self._scene_pub = rospy.Publisher('planning_scene',
00062                                           PlanningScene,
00063                                           queue_size=10)
00064 
00065         # track the attached and collision objects
00066         self._mutex = thread.allocate_lock()
00067         # these are updated based what the planning scene actually contains
00068         self._attached = list()
00069         self._collision = list()
00070         # these are updated based on internal state
00071         self._objects = dict()
00072         self._attached_objects = dict()
00073         self._removed = dict()
00074         self._attached_removed = dict()
00075         self._colors = dict()
00076 
00077         # get the initial planning scene
00078         if init_from_service:
00079             rospy.loginfo('Waiting for get_planning_scene')
00080             rospy.wait_for_service('get_planning_scene')
00081             self._service = rospy.ServiceProxy('get_planning_scene',
00082                                                GetPlanningScene)
00083             try:
00084                 req = PlanningSceneComponents()
00085                 req.components = sum([
00086                     PlanningSceneComponents.WORLD_OBJECT_NAMES,
00087                     PlanningSceneComponents.WORLD_OBJECT_GEOMETRY,
00088                     PlanningSceneComponents.ROBOT_STATE_ATTACHED_OBJECTS])
00089                 scene = self._service(req)
00090                 self.sceneCb(scene.scene, initial=True)
00091             except rospy.ServiceException as e:
00092                 rospy.logerr('Failed to get initial planning scene, results may be wonky: %s', e)
00093 
00094         # subscribe to planning scene
00095         rospy.Subscriber('move_group/monitored_planning_scene',
00096                          PlanningScene,
00097                          self.sceneCb)
00098 
00099     ## @brief Clear the planning scene of all objects
00100     def clear(self):
00101         for name in self.getKnownCollisionObjects():
00102             self.removeCollisionObject(name, False)
00103         for name in self.getKnownAttachedObjects():
00104             self.removeAttachedObject(name, False)
00105         self.waitForSync()
00106 
00107     ## @brief Make a mesh collision object
00108     ## @param name Name of the object
00109     ## @param pose A geometry_msgs/Pose for the object
00110     ## @param filename The mesh file to load
00111     def makeMesh(self, name, pose, filename):
00112         if not use_pyassimp:
00113             rospy.logerr('pyassimp is broken on your platform, cannot load meshes')
00114             return
00115         scene = pyassimp.load(filename)
00116         if not scene.meshes:
00117             rospy.logerr('Unable to load mesh')
00118             return
00119 
00120         mesh = Mesh()
00121         for face in scene.meshes[0].faces:
00122             triangle = MeshTriangle()
00123             if len(face.indices) == 3:
00124                 triangle.vertex_indices = [face.indices[0],
00125                                            face.indices[1],
00126                                            face.indices[2]]
00127             mesh.triangles.append(triangle)
00128         for vertex in scene.meshes[0].vertices:
00129             point = Point()
00130             point.x = vertex[0]
00131             point.y = vertex[1]
00132             point.z = vertex[2]
00133             mesh.vertices.append(point)
00134         pyassimp.release(scene)
00135 
00136         o = CollisionObject()
00137         o.header.stamp = rospy.Time.now()
00138         o.header.frame_id = self._fixed_frame
00139         o.id = name
00140         o.meshes.append(mesh)
00141         o.mesh_poses.append(pose)
00142         o.operation = o.ADD
00143         return o
00144 
00145     ## @brief Make a solid primitive collision object
00146     ## @param name Name of the object
00147     ## @param solid The solid primitive to add
00148     ## @param pose A geometry_msgs/Pose for the object
00149     ## @param wait When true, we wait for planning scene to actually update,
00150     ##             this provides immunity against lost messages.
00151     def makeSolidPrimitive(self, name, solid, pose):
00152         o = CollisionObject()
00153         o.header.stamp = rospy.Time.now()
00154         o.header.frame_id = self._fixed_frame
00155         o.id = name
00156         o.primitives.append(solid)
00157         o.primitive_poses.append(pose)
00158         o.operation = o.ADD
00159         return o
00160 
00161     ## @brief Make an attachedCollisionObject
00162     def makeAttached(self, link_name, obj, touch_links, detach_posture,
00163                      weight):
00164         o = AttachedCollisionObject()
00165         o.link_name = link_name
00166         o.object = obj
00167         if touch_links:
00168             o.touch_links = touch_links
00169         if detach_posture:
00170             o.detach_posture = detach_posture
00171         o.weight = weight
00172         return o
00173 
00174     ## @brief Insert a mesh into the planning scene
00175     ## @param name Name of the object
00176     ## @param pose A geometry_msgs/Pose for the object
00177     ## @param filename The mesh file to load
00178     ## @param wait When true, we wait for planning scene to actually update,
00179     ##             this provides immunity against lost messages.
00180     def addMesh(self, name, pose, filename, wait=True):
00181         o = self.makeMesh(name, pose, filename)
00182         self._objects[name] = o
00183         self._pub.publish(o)
00184         if wait:
00185             self.waitForSync()
00186 
00187     ## @brief Attach a mesh into the planning scene
00188     ## @param name Name of the object
00189     ## @param pose A geometry_msgs/Pose for the object
00190     ## @param filename The mesh file to load
00191     ## @param wait When true, we wait for planning scene to actually update,
00192     ##             this provides immunity against lost messages.
00193     def attachMesh(self, name, pose, filename, link_name, touch_links=None,
00194                    detach_posture=None, weight=0.0, wait=True):
00195         o = self.makeMesh(name, pose, filename)
00196         o.header.frame_id = link_name
00197         a = self.makeAttached(link_name, o, touch_links, detach_posture,
00198                               weight)
00199         self._attached_objects[name] = a
00200         self._attached_pub.publish(a)
00201         if wait:
00202             self.waitForSync()
00203 
00204     ## @brief Insert a solid primitive into planning scene
00205     ## @param wait When true, we wait for planning scene to actually update,
00206     ##             this provides immunity against lost messages.
00207     def addSolidPrimitive(self, name, solid, pose, wait=True):
00208         o = self.makeSolidPrimitive(name, solid, pose)
00209         self._objects[name] = o
00210         self._pub.publish(o)
00211         if wait:
00212             self.waitForSync()
00213 
00214     ## @brief Insert new cylinder into planning scene
00215     ## @param wait When true, we wait for planning scene to actually update,
00216     ##             this provides immunity against lost messages.
00217     def addCylinder(self, name, height, radius, x, y, z, wait=True):
00218         s = SolidPrimitive()
00219         s.dimensions = [height, radius]
00220         s.type = s.CYLINDER
00221 
00222         ps = PoseStamped()
00223         ps.header.frame_id = self._fixed_frame
00224         ps.pose.position.x = x
00225         ps.pose.position.y = y
00226         ps.pose.position.z = z
00227         ps.pose.orientation.w = 1.0
00228 
00229         self.addSolidPrimitive(name, s, ps.pose, wait)
00230 
00231     ## @brief Insert new box into planning scene
00232     ## @param name Name of the object
00233     ## @param size_x The x-dimensions size of the box
00234     ## @param size_y The y-dimensions size of the box
00235     ## @param size_z The z-dimensions size of the box
00236     ## @param x The x position in link_name frame
00237     ## @param y The y position in link_name frame
00238     ## @param z The z position in link_name frame
00239     ## @param wait When true, we wait for planning scene to actually update,
00240     ##             this provides immunity against lost messages.
00241     def addBox(self, name, size_x, size_y, size_z, x, y, z, wait=True):
00242         s = SolidPrimitive()
00243         s.dimensions = [size_x, size_y, size_z]
00244         s.type = s.BOX
00245 
00246         ps = PoseStamped()
00247         ps.header.frame_id = self._fixed_frame
00248         ps.pose.position.x = x
00249         ps.pose.position.y = y
00250         ps.pose.position.z = z
00251         ps.pose.orientation.w = 1.0
00252 
00253         self.addSolidPrimitive(name, s, ps.pose, wait)
00254 
00255     ## @brief Attach a box into the planning scene
00256     ## @param name Name of the object
00257     ## @param size_x The x-dimensions size of the box
00258     ## @param size_y The y-dimensions size of the box
00259     ## @param size_z The z-dimensions size of the box
00260     ## @param x The x position in link_name frame
00261     ## @param y The y position in link_name frame
00262     ## @param z The z position in link_name frame
00263     ## @param link_name Name of link to attach this object to
00264     ## @param touch_links Names of robot links that can touch this object
00265     ## @param wait When true, we wait for planning scene to actually update,
00266     ##             this provides immunity against lost messages.
00267     def attachBox(self, name, size_x, size_y, size_z, x, y, z, link_name,
00268                   touch_links=None, detach_posture=None, weight=0.0,
00269                   wait=True):
00270         s = SolidPrimitive()
00271         s.dimensions = [size_x, size_y, size_z]
00272         s.type = s.BOX
00273 
00274         p = Pose()
00275         p.position.x = x
00276         p.position.y = y
00277         p.position.z = z
00278         p.orientation.w = 1.0
00279 
00280         o = self.makeSolidPrimitive(name, s, p)
00281         o.header.frame_id = link_name
00282         a = self.makeAttached(link_name, o, touch_links, detach_posture, weight)
00283         self._attached_objects[name] = a
00284         self._attached_pub.publish(a)
00285         if wait:
00286             self.waitForSync()
00287 
00288     ## @brief Insert new cube to planning scene
00289     ## @param wait When true, we wait for planning scene to actually update,
00290     ##             this provides immunity against lost messages.
00291     def addCube(self, name, size, x, y, z, wait=True):
00292         self.addBox(name, size, size, size, x, y, z, wait)
00293 
00294     ## @brief Send message to remove object
00295     ## @param wait When true, we wait for planning scene to actually update,
00296     ##             this provides immunity against lost messages.
00297     def removeCollisionObject(self, name, wait=True):
00298         """ Remove an object. """
00299         o = CollisionObject()
00300         o.header.stamp = rospy.Time.now()
00301         o.header.frame_id = self._fixed_frame
00302         o.id = name
00303         o.operation = o.REMOVE
00304 
00305         try:
00306             del self._objects[name]
00307             self._removed[name] = o
00308         except KeyError:
00309             pass
00310 
00311         self._pub.publish(o)
00312         if wait:
00313             self.waitForSync()
00314 
00315     ## @brief Send message to remove object
00316     ## @param wait When true, we wait for planning scene to actually update,
00317     ##             this provides immunity against lost messages.
00318     def removeAttachedObject(self, name, wait=True):
00319         """ Remove an attached object. """
00320         o = AttachedCollisionObject()
00321         o.object.operation = CollisionObject.REMOVE
00322         #o.link_name = ??
00323         o.object.id = name
00324 
00325         try:
00326             del self._attached_objects[name]
00327             self._attached_removed[name] = o
00328         except KeyError:
00329             pass
00330 
00331         self._attached_pub.publish(o)
00332         if wait:
00333             self.waitForSync()
00334 
00335     ## @brief Update the object lists from a PlanningScene message
00336     def sceneCb(self, msg, initial=False):
00337         """ Recieve updates from move_group. """
00338         self._mutex.acquire()
00339         for obj in msg.world.collision_objects:
00340             try:
00341                 if obj.operation == obj.ADD:
00342                     self._collision.append(obj.id)
00343                     rospy.logdebug('ObjectManager: Added Collision Obj "%s"',
00344                                    obj.id)
00345                     if initial:
00346                         # this is our initial planning scene, hold onto each object
00347                         self._objects[obj.id] = obj
00348                 elif obj.operation == obj.REMOVE:
00349                     self._collision.remove(obj.id)
00350                     self._removed.pop(obj.id, None)
00351                     rospy.logdebug('ObjectManager: Removed Collision Obj "%s"',
00352                                    obj.id)
00353             except ValueError:
00354                 pass
00355         self._attached = list()
00356         for obj in msg.robot_state.attached_collision_objects:
00357             rospy.logdebug('ObjectManager: attached collision Obj "%s"',
00358                            obj.object.id)
00359             self._attached.append(obj.object.id)
00360             if initial:
00361                 # this is our initial planning scene, hold onto each object
00362                 self._attached_objects[obj.object.id] = obj
00363         self._mutex.release()
00364 
00365     ## @brief Get a list of names of collision objects
00366     def getKnownCollisionObjects(self):
00367         self._mutex.acquire()
00368         l = copy.deepcopy(self._collision)
00369         self._mutex.release()
00370         return l
00371 
00372     ## @brief Get a list of names of attached objects
00373     def getKnownAttachedObjects(self):
00374         self._mutex.acquire()
00375         l = copy.deepcopy(self._attached)
00376         self._mutex.release()
00377         return l
00378 
00379     ## @brief Wait for sync
00380     def waitForSync(self, max_time=2.0):
00381         sync = False
00382         t = rospy.Time.now()
00383         while not sync:
00384             sync = True
00385             # delete objects that should be gone
00386             for name in self._collision:
00387                 if name in self._removed.keys():
00388                     # should be removed, is not
00389                     self.removeCollisionObject(name, False)
00390                     sync = False
00391             for name in self._attached:
00392                 if name in self._attached_removed.keys():
00393                     # should be removed, is not
00394                     self.removeAttachedObject(name, False)
00395                     sync = False
00396             # add missing objects
00397             for name in self._objects.keys():
00398                 if name not in self._collision + self._attached:
00399                     self._pub.publish(self._objects[name])
00400                     sync = False
00401             for name in self._attached_objects.keys():
00402                 if name not in self._attached:
00403                     self._attached_pub.publish(self._attached_objects[name])
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         self._scene_pub.publish(p)
00431 


moveit_python
Author(s): Michael Ferguson
autogenerated on Fri Aug 26 2016 13:12:36