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


moveit_python
Author(s): Michael Ferguson
autogenerated on Fri Aug 28 2015 11:32:16