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
00029
00030
00031
00032
00033
00034
00035 import rospy
00036 import conversions
00037
00038 from moveit_msgs.msg import CollisionObject, AttachedCollisionObject
00039 from moveit_ros_planning_interface import _moveit_planning_scene_interface
00040 from geometry_msgs.msg import PoseStamped, Pose, Point
00041 from shape_msgs.msg import SolidPrimitive, Plane, Mesh, MeshTriangle
00042 from exception import MoveItCommanderException
00043
00044 try:
00045 from pyassimp import pyassimp
00046 except:
00047
00048 import pyassimp
00049
00050
00051
00052
00053 class PlanningSceneInterface(object):
00054 """ Simple interface to making updates to a planning scene """
00055
00056 def __init__(self):
00057 """ Create a planning scene interface; it uses both C++ wrapped methods and scene manipulation topics. """
00058 self._psi = _moveit_planning_scene_interface.PlanningSceneInterface()
00059
00060 self._pub_co = rospy.Publisher('/collision_object', CollisionObject, queue_size=100)
00061 self._pub_aco = rospy.Publisher('/attached_collision_object', AttachedCollisionObject, queue_size=100)
00062
00063 def __make_sphere(self, name, pose, radius):
00064 co = CollisionObject()
00065 co.operation = CollisionObject.ADD
00066 co.id = name
00067 co.header = pose.header
00068 sphere = SolidPrimitive()
00069 sphere.type = SolidPrimitive.SPHERE
00070 sphere.dimensions = [radius]
00071 co.primitives = [sphere]
00072 co.primitive_poses = [pose.pose]
00073 return co
00074
00075 def add_sphere(self, name, pose, radius = 1):
00076 """
00077 Add a sphere to the planning scene
00078 """
00079 self._pub_co.publish(self.__make_sphere(name, pose, radius))
00080
00081 def __make_box(self, name, pose, size):
00082 co = CollisionObject()
00083 co.operation = CollisionObject.ADD
00084 co.id = name
00085 co.header = pose.header
00086 box = SolidPrimitive()
00087 box.type = SolidPrimitive.BOX
00088 box.dimensions = list(size)
00089 co.primitives = [box]
00090 co.primitive_poses = [pose.pose]
00091 return co
00092
00093 def __make_mesh(self, name, pose, filename, scale = (1, 1, 1)):
00094 co = CollisionObject()
00095 scene = pyassimp.load(filename)
00096 if not scene.meshes:
00097 raise MoveItCommanderException("There are no meshes in the file")
00098 co.operation = CollisionObject.ADD
00099 co.id = name
00100 co.header = pose.header
00101
00102 mesh = Mesh()
00103 for face in scene.meshes[0].faces:
00104 triangle = MeshTriangle()
00105 if len(face.indices) == 3:
00106 triangle.vertex_indices = [face.indices[0], face.indices[1], face.indices[2]]
00107 mesh.triangles.append(triangle)
00108 for vertex in scene.meshes[0].vertices:
00109 point = Point()
00110 point.x = vertex[0]*scale[0]
00111 point.y = vertex[1]*scale[1]
00112 point.z = vertex[2]*scale[2]
00113 mesh.vertices.append(point)
00114 co.meshes = [mesh]
00115 co.mesh_poses = [pose.pose]
00116 pyassimp.release(scene)
00117 return co
00118
00119 def __make_existing(self, name):
00120 """
00121 Create an empty Collision Object, used when the object already exists
00122 """
00123 co = CollisionObject()
00124 co.id = name
00125 return co
00126
00127 def add_mesh(self, name, pose, filename, size = (1, 1, 1)):
00128 """
00129 Add a mesh to the planning scene
00130 """
00131 self._pub_co.publish(self.__make_mesh(name, pose, filename, size))
00132
00133 def add_box(self, name, pose, size = (1, 1, 1)):
00134 """
00135 Add a box to the planning scene
00136 """
00137 self._pub_co.publish(self.__make_box(name, pose, size))
00138
00139 def add_plane(self, name, pose, normal = (0, 0, 1), offset = 0):
00140 """ Add a plane to the planning scene """
00141 co = CollisionObject()
00142 co.operation = CollisionObject.ADD
00143 co.id = name
00144 co.header = pose.header
00145 p = Plane()
00146 p.coef = list(normal)
00147 p.coef.append(offset)
00148 co.planes = [p]
00149 co.plane_poses = [pose.pose]
00150 self._pub_co.publish(co)
00151
00152 def attach_mesh(self, link, name, pose = None, filename = '', size = (1, 1, 1), touch_links = []):
00153 aco = AttachedCollisionObject()
00154 if pose!=None and filename:
00155 aco.object = self.__make_mesh(name, pose, filename, size)
00156 else:
00157 aco.object = self.__make_existing(name)
00158 aco.link_name = link
00159 aco.touch_links = [link]
00160 if len(touch_links) > 0:
00161 aco.touch_links = touch_links
00162 self._pub_aco.publish(aco)
00163
00164 def attach_box(self, link, name, pose = None, size = (1, 1, 1), touch_links = []):
00165 aco = AttachedCollisionObject()
00166 if pose!=None:
00167 aco.object = self.__make_box(name, pose, size)
00168 else:
00169 aco.object = self.__make_existing(name)
00170 aco.link_name = link
00171 if len(touch_links) > 0:
00172 aco.touch_links = touch_links
00173 else:
00174 aco.touch_links = [link]
00175 self._pub_aco.publish(aco)
00176
00177 def remove_world_object(self, name = None):
00178 """
00179 Remove an object from planning scene, or all if no name is provided
00180 """
00181 co = CollisionObject()
00182 co.operation = CollisionObject.REMOVE
00183 if name != None:
00184 co.id = name
00185 self._pub_co.publish(co)
00186
00187 def remove_attached_object(self, link, name = None):
00188 """
00189 Remove an attached object from planning scene, or all objects attached to this link if no name is provided
00190 """
00191 aco = AttachedCollisionObject()
00192 aco.object.operation = CollisionObject.REMOVE
00193 aco.link_name = link
00194 if name != None:
00195 aco.object.id = name
00196 self._pub_aco.publish(aco)
00197
00198 def get_known_object_names(self, with_type = False):
00199 """
00200 Get the names of all known objects in the world. If with_type is set to true, only return objects that have a known type.
00201 """
00202 return self._psi.get_known_object_names(with_type)
00203
00204 def get_known_object_names_in_roi(self, minx, miny, minz, maxx, maxy, maxz, with_type = False):
00205 """
00206 Get the names of known objects in the world that are located within a bounding region (specified in the frame reported by
00207 get_planning_frame()). If with_type is set to true, only return objects that have a known type.
00208 """
00209 return self._psi.get_known_object_names_in_roi(minx, miny, minz, maxx, maxy, maxz, with_type)
00210
00211 def get_object_poses(self, object_ids):
00212 """
00213 Get the poses from the objects identified by the given object ids list.
00214 """
00215 ser_ops = self._psi.get_object_poses(object_ids)
00216 ops = dict()
00217 for key in ser_ops:
00218 msg = Pose()
00219 conversions.msg_from_string(msg, ser_ops[key])
00220 ops[key] = msg
00221 return ops
00222
00223 def get_objects(self, object_ids = []):
00224 """
00225 Get the objects identified by the given object ids list. If no ids are provided, return all the known objects.
00226 """
00227 ser_objs = self._psi.get_objects(object_ids)
00228 objs = dict()
00229 for key in ser_objs:
00230 msg = CollisionObject()
00231 conversions.msg_from_string(msg, ser_objs[key])
00232 objs[key] = msg
00233 return objs
00234
00235 def get_attached_objects(self, object_ids = []):
00236 """
00237 Get the attached objects identified by the given object ids list. If no ids are provided, return all the attached objects.
00238 """
00239 ser_aobjs = self._psi.get_attached_objects(object_ids)
00240 aobjs = dict()
00241 for key in ser_aobjs:
00242 msg = AttachedCollisionObject()
00243 conversions.msg_from_string(msg, ser_aobjs[key])
00244 aobjs[key] = msg
00245 return aobjs