00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
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
00040
00041
00042
00043
00044 class PlanningSceneInterface(object):
00045 def __init__(self, frame, init_from_service=True):
00046 self._fixed_frame = frame
00047
00048
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
00060 self._mutex = thread.allocate_lock()
00061
00062 self._attached = list()
00063 self._collision = list()
00064
00065 self._objects = dict()
00066 self._attached_objects = dict()
00067 self._removed = dict()
00068 self._attached_removed = dict()
00069 self._colors = dict()
00070
00071
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
00089 rospy.Subscriber('move_group/monitored_planning_scene',
00090 PlanningScene,
00091 self.sceneCb)
00092
00093
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
00102
00103
00104
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
00137
00138
00139
00140
00141
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
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
00166
00167
00168
00169
00170
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
00179
00180
00181
00182
00183
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
00196
00197
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
00206
00207
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
00223
00224
00225
00226
00227
00228
00229
00230
00231
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
00247
00248
00249
00250
00251
00252
00253
00254
00255
00256
00257
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
00280
00281
00282 def addCube(self, name, size, x, y, z, wait=True):
00283 self.addBox(name, size, size, size, x, y, z, wait)
00284
00285
00286
00287
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
00307
00308
00309 def removeAttachedObject(self, name, wait=True):
00310 """ Remove an attached object. """
00311 o = AttachedCollisionObject()
00312 o.object.operation = CollisionObject.REMOVE
00313
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
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
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
00353 self._attached_objects[obj.object.id] = obj
00354 self._mutex.release()
00355
00356
00357 def getKnownCollisionObjects(self):
00358 self._mutex.acquire()
00359 l = copy.deepcopy(self._collision)
00360 self._mutex.release()
00361 return l
00362
00363
00364 def getKnownAttachedObjects(self):
00365 self._mutex.acquire()
00366 l = copy.deepcopy(self._attached)
00367 self._mutex.release()
00368 return l
00369
00370
00371 def waitForSync(self, max_time=2.0):
00372 sync = False
00373 t = rospy.Time.now()
00374 while not sync:
00375 sync = True
00376
00377 for name in self._collision:
00378 if name in self._removed.keys():
00379
00380 self.removeCollisionObject(name, False)
00381 sync = False
00382 for name in self._attached:
00383 if name in self._attached_removed.keys():
00384
00385 self.removeAttachedObject(name, False)
00386 sync = False
00387
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
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
00404 def setColor(self, name, r, g, b, a=0.9):
00405
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
00415 def sendColors(self):
00416
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