32 from pyassimp
import pyassimp
40 from moveit_msgs.msg
import CollisionObject, AttachedCollisionObject
41 from moveit_msgs.msg
import PlanningScene, PlanningSceneComponents, ObjectColor
42 from moveit_msgs.srv
import GetPlanningScene, ApplyPlanningScene
43 from shape_msgs.msg
import MeshTriangle, Mesh, SolidPrimitive, Plane
52 def __init__(self, frame, ns='', init_from_service=True):
54 if not isinstance(ns, basestring):
55 rospy.logerr(
'Namespace must be a string!')
57 elif not ns.endswith(
'/'):
65 self.
_apply_service = rospy.ServiceProxy(ns +
'apply_planning_scene', ApplyPlanningScene)
80 rospy.loginfo(
'Waiting for get_planning_scene')
81 rospy.wait_for_service(ns +
'get_planning_scene')
82 self.
_service = rospy.ServiceProxy(ns +
'get_planning_scene',
85 req = PlanningSceneComponents()
86 req.components = sum([
87 PlanningSceneComponents.WORLD_OBJECT_NAMES,
88 PlanningSceneComponents.WORLD_OBJECT_GEOMETRY,
89 PlanningSceneComponents.ROBOT_STATE_ATTACHED_OBJECTS])
91 self.
sceneCb(scene.scene, initial=
True)
92 except rospy.ServiceException
as e:
93 rospy.logerr(
'Failed to get initial planning scene, results may be wonky: %s', e)
96 rospy.Subscriber(ns +
'move_group/monitored_planning_scene',
104 def sendUpdate(self, collision_object, attached_collision_object, use_service=True):
108 ps.world.collision_objects.append(collision_object)
110 if attached_collision_object:
111 ps.robot_state.attached_collision_objects.append(attached_collision_object)
114 resp = self._apply_service.call(ps)
116 rospy.logerr(
"Could not apply planning scene diff.")
118 self._scene_pub.publish(ps)
134 rospy.logerr(
'pyassimp is broken on your platform, cannot load meshes')
136 scene = pyassimp.load(filename)
138 rospy.logerr(
'Unable to load mesh')
142 for face
in scene.meshes[0].faces:
143 triangle = MeshTriangle()
144 if len(face.indices) == 3:
145 triangle.vertex_indices = [face.indices[0],
148 mesh.triangles.append(triangle)
149 for vertex
in scene.meshes[0].vertices:
154 mesh.vertices.append(point)
155 pyassimp.release(scene)
157 o = CollisionObject()
158 o.header.stamp = rospy.Time.now()
161 o.meshes.append(mesh)
162 o.mesh_poses.append(pose)
171 o = CollisionObject()
172 o.header.stamp = rospy.Time.now()
175 o.primitives.append(solid)
176 o.primitive_poses.append(pose)
181 def makeAttached(self, link_name, obj, touch_links, detach_posture,
183 o = AttachedCollisionObject()
184 o.link_name = link_name
187 o.touch_links = touch_links
189 o.detach_posture = detach_posture
198 def addMesh(self, name, pose, filename, use_service=True):
199 o = self.
makeMesh(name, pose, filename)
208 def attachMesh(self, name, pose, filename, link_name, touch_links=None,
209 detach_posture=
None, weight=0.0, use_service=
True):
210 o = self.
makeMesh(name, pose, filename)
211 o.header.frame_id = link_name
212 a = self.
makeAttached(link_name, o, touch_links, detach_posture,
226 def addCylinder(self, name, height, radius, x, y, z, use_service=True):
228 s.dimensions = [height, radius]
233 ps.pose.position.x = x
234 ps.pose.position.y = y
235 ps.pose.position.z = z
236 ps.pose.orientation.w = 1.0
249 def addBox(self, name, size_x, size_y, size_z, x, y, z, use_service=True):
251 s.dimensions = [size_x, size_y, size_z]
256 ps.pose.position.x = x
257 ps.pose.position.y = y
258 ps.pose.position.z = z
259 ps.pose.orientation.w = 1.0
274 def attachBox(self, name, size_x, size_y, size_z, x, y, z, link_name,
275 touch_links=
None, detach_posture=
None, weight=0.0,
278 s.dimensions = [size_x, size_y, size_z]
285 p.orientation.w = 1.0
287 o.header.frame_id = link_name
288 a = self.
makeAttached(link_name, o, touch_links, detach_posture, weight)
294 def addCube(self, name, size, x, y, z, use_service=True):
295 self.
addBox(name, size, size, size, x, y, z, use_service)
300 """ Remove an object. """ 301 o = CollisionObject()
302 o.header.stamp = rospy.Time.now()
305 o.operation = o.REMOVE
318 """ Remove an attached object. """ 319 o = AttachedCollisionObject()
320 o.object.operation = CollisionObject.REMOVE
333 """ Recieve updates from move_group. """ 334 self._mutex.acquire()
335 for obj
in msg.world.collision_objects:
337 if obj.operation == obj.ADD:
338 self._collision.append(obj.id)
339 rospy.logdebug(
'ObjectManager: Added Collision Obj "%s"',
344 elif obj.operation == obj.REMOVE:
345 self._collision.remove(obj.id)
346 self._removed.pop(obj.id,
None)
347 rospy.logdebug(
'ObjectManager: Removed Collision Obj "%s"',
352 for obj
in msg.robot_state.attached_collision_objects:
353 rospy.logdebug(
'ObjectManager: attached collision Obj "%s"',
355 self._attached.append(obj.object.id)
359 self._mutex.release()
363 self._mutex.acquire()
365 self._mutex.release()
370 self._mutex.acquire()
372 self._mutex.release()
383 if name
in self._removed.keys():
385 rospy.logwarn(
'ObjectManager: %s not removed yet', name)
389 if name
in self._attached_removed.keys():
391 rospy.logwarn(
'ObjectManager: Attached object name: %s not removed yet', name)
395 for name
in self._objects.keys():
397 rospy.logwarn(
'ObjectManager: %s not added yet', name)
400 for name
in self._attached_objects.keys():
402 rospy.logwarn(
'ObjectManager: %s not attached yet', name)
406 if rospy.Time.now() - t > rospy.Duration(max_time):
407 rospy.logerr(
'ObjectManager: sync timed out.')
409 rospy.logdebug(
'ObjectManager: waiting for sync.')
415 color = ObjectColor()
428 for color
in self._colors.values():
429 p.object_colors.append(color)
430 resp = self._apply_service.call(p)
432 rospy.logerr(
"Could not update colors through service, using topic instead.")
433 self._scene_pub.publish(p)
def sendUpdate(self, collision_object, attached_collision_object, use_service=True)
Send new update to planning scene.
def removeCollisionObject(self, name, use_service=True)
Send message to remove object.
def sceneCb(self, msg, initial=False)
Update the object lists from a PlanningScene message.
def getKnownCollisionObjects(self)
Get a list of names of collision objects.
def attachMesh(self, name, pose, filename, link_name, touch_links=None, detach_posture=None, weight=0.0, use_service=True)
Attach a mesh into the planning scene.
def sendColors(self)
Actually send the colors to MoveIt!
def addBox(self, name, size_x, size_y, size_z, x, y, z, use_service=True)
Insert new box into planning scene.
def waitForSync(self, max_time=2.0)
Wait for sync.
def addCylinder(self, name, height, radius, x, y, z, use_service=True)
Insert new cylinder into planning scene.
def clear(self)
Clear the planning scene of all objects.
def setColor(self, name, r, g, b, a=0.9)
Set the color of an object.
def getKnownAttachedObjects(self)
Get a list of names of attached objects.
def makeSolidPrimitive(self, name, solid, pose)
Make a solid primitive collision object.
def makeMesh(self, name, pose, filename)
Make a mesh collision object.
def attachBox(self, name, size_x, size_y, size_z, x, y, z, link_name, touch_links=None, detach_posture=None, weight=0.0, use_service=True)
Attach a box into the planning scene.
def addCube(self, name, size, x, y, z, use_service=True)
Insert new cube to planning scene.
def makeAttached(self, link_name, obj, touch_links, detach_posture, weight)
Make an attachedCollisionObject.
def addMesh(self, name, pose, filename, use_service=True)
Insert a mesh into the planning scene.
def addSolidPrimitive(self, name, solid, pose, use_service=True)
Insert a solid primitive into planning scene.
def __init__(self, frame, ns='', init_from_service=True)
A class for managing the state of the planning scene.
def removeAttachedObject(self, name, use_service=True)
Send message to remove object.