$search
00001 """autogenerated by genmsg_py from mesh.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import arm_navigation_msgs.msg 00006 import geometry_msgs.msg 00007 00008 class mesh(roslib.message.Message): 00009 _md5sum = "1730abcb9e222ac87717c4ce8068089b" 00010 _type = "srs_object_database_msgs/mesh" 00011 _has_header = False #flag to mark the presence of a Header object 00012 _full_text = """int32 objectId 00013 arm_navigation_msgs/Shape mesh 00014 string type 00015 uint8[] data 00016 ================================================================================ 00017 MSG: arm_navigation_msgs/Shape 00018 byte SPHERE=0 00019 byte BOX=1 00020 byte CYLINDER=2 00021 byte MESH=3 00022 00023 byte type 00024 00025 00026 #### define sphere, box, cylinder #### 00027 # the origin of each shape is considered at the shape's center 00028 00029 # for sphere 00030 # radius := dimensions[0] 00031 00032 # for cylinder 00033 # radius := dimensions[0] 00034 # length := dimensions[1] 00035 # the length is along the Z axis 00036 00037 # for box 00038 # size_x := dimensions[0] 00039 # size_y := dimensions[1] 00040 # size_z := dimensions[2] 00041 float64[] dimensions 00042 00043 00044 #### define mesh #### 00045 00046 # list of triangles; triangle k is defined by tre vertices located 00047 # at indices triangles[3k], triangles[3k+1], triangles[3k+2] 00048 int32[] triangles 00049 geometry_msgs/Point[] vertices 00050 00051 ================================================================================ 00052 MSG: geometry_msgs/Point 00053 # This contains the position of a point in free space 00054 float64 x 00055 float64 y 00056 float64 z 00057 00058 """ 00059 __slots__ = ['objectId','mesh','type','data'] 00060 _slot_types = ['int32','arm_navigation_msgs/Shape','string','uint8[]'] 00061 00062 def __init__(self, *args, **kwds): 00063 """ 00064 Constructor. Any message fields that are implicitly/explicitly 00065 set to None will be assigned a default value. The recommend 00066 use is keyword arguments as this is more robust to future message 00067 changes. You cannot mix in-order arguments and keyword arguments. 00068 00069 The available fields are: 00070 objectId,mesh,type,data 00071 00072 @param args: complete set of field values, in .msg order 00073 @param kwds: use keyword arguments corresponding to message field names 00074 to set specific fields. 00075 """ 00076 if args or kwds: 00077 super(mesh, self).__init__(*args, **kwds) 00078 #message fields cannot be None, assign default values for those that are 00079 if self.objectId is None: 00080 self.objectId = 0 00081 if self.mesh is None: 00082 self.mesh = arm_navigation_msgs.msg.Shape() 00083 if self.type is None: 00084 self.type = '' 00085 if self.data is None: 00086 self.data = '' 00087 else: 00088 self.objectId = 0 00089 self.mesh = arm_navigation_msgs.msg.Shape() 00090 self.type = '' 00091 self.data = '' 00092 00093 def _get_types(self): 00094 """ 00095 internal API method 00096 """ 00097 return self._slot_types 00098 00099 def serialize(self, buff): 00100 """ 00101 serialize message into buffer 00102 @param buff: buffer 00103 @type buff: StringIO 00104 """ 00105 try: 00106 _x = self 00107 buff.write(_struct_ib.pack(_x.objectId, _x.mesh.type)) 00108 length = len(self.mesh.dimensions) 00109 buff.write(_struct_I.pack(length)) 00110 pattern = '<%sd'%length 00111 buff.write(struct.pack(pattern, *self.mesh.dimensions)) 00112 length = len(self.mesh.triangles) 00113 buff.write(_struct_I.pack(length)) 00114 pattern = '<%si'%length 00115 buff.write(struct.pack(pattern, *self.mesh.triangles)) 00116 length = len(self.mesh.vertices) 00117 buff.write(_struct_I.pack(length)) 00118 for val1 in self.mesh.vertices: 00119 _x = val1 00120 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00121 _x = self.type 00122 length = len(_x) 00123 buff.write(struct.pack('<I%ss'%length, length, _x)) 00124 _x = self.data 00125 length = len(_x) 00126 # - if encoded as a list instead, serialize as bytes instead of string 00127 if type(_x) in [list, tuple]: 00128 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00129 else: 00130 buff.write(struct.pack('<I%ss'%length, length, _x)) 00131 except struct.error as se: self._check_types(se) 00132 except TypeError as te: self._check_types(te) 00133 00134 def deserialize(self, str): 00135 """ 00136 unpack serialized message in str into this message instance 00137 @param str: byte array of serialized message 00138 @type str: str 00139 """ 00140 try: 00141 if self.mesh is None: 00142 self.mesh = arm_navigation_msgs.msg.Shape() 00143 end = 0 00144 _x = self 00145 start = end 00146 end += 5 00147 (_x.objectId, _x.mesh.type,) = _struct_ib.unpack(str[start:end]) 00148 start = end 00149 end += 4 00150 (length,) = _struct_I.unpack(str[start:end]) 00151 pattern = '<%sd'%length 00152 start = end 00153 end += struct.calcsize(pattern) 00154 self.mesh.dimensions = struct.unpack(pattern, str[start:end]) 00155 start = end 00156 end += 4 00157 (length,) = _struct_I.unpack(str[start:end]) 00158 pattern = '<%si'%length 00159 start = end 00160 end += struct.calcsize(pattern) 00161 self.mesh.triangles = struct.unpack(pattern, str[start:end]) 00162 start = end 00163 end += 4 00164 (length,) = _struct_I.unpack(str[start:end]) 00165 self.mesh.vertices = [] 00166 for i in range(0, length): 00167 val1 = geometry_msgs.msg.Point() 00168 _x = val1 00169 start = end 00170 end += 24 00171 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00172 self.mesh.vertices.append(val1) 00173 start = end 00174 end += 4 00175 (length,) = _struct_I.unpack(str[start:end]) 00176 start = end 00177 end += length 00178 self.type = str[start:end] 00179 start = end 00180 end += 4 00181 (length,) = _struct_I.unpack(str[start:end]) 00182 start = end 00183 end += length 00184 self.data = str[start:end] 00185 return self 00186 except struct.error as e: 00187 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00188 00189 00190 def serialize_numpy(self, buff, numpy): 00191 """ 00192 serialize message with numpy array types into buffer 00193 @param buff: buffer 00194 @type buff: StringIO 00195 @param numpy: numpy python module 00196 @type numpy module 00197 """ 00198 try: 00199 _x = self 00200 buff.write(_struct_ib.pack(_x.objectId, _x.mesh.type)) 00201 length = len(self.mesh.dimensions) 00202 buff.write(_struct_I.pack(length)) 00203 pattern = '<%sd'%length 00204 buff.write(self.mesh.dimensions.tostring()) 00205 length = len(self.mesh.triangles) 00206 buff.write(_struct_I.pack(length)) 00207 pattern = '<%si'%length 00208 buff.write(self.mesh.triangles.tostring()) 00209 length = len(self.mesh.vertices) 00210 buff.write(_struct_I.pack(length)) 00211 for val1 in self.mesh.vertices: 00212 _x = val1 00213 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z)) 00214 _x = self.type 00215 length = len(_x) 00216 buff.write(struct.pack('<I%ss'%length, length, _x)) 00217 _x = self.data 00218 length = len(_x) 00219 # - if encoded as a list instead, serialize as bytes instead of string 00220 if type(_x) in [list, tuple]: 00221 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00222 else: 00223 buff.write(struct.pack('<I%ss'%length, length, _x)) 00224 except struct.error as se: self._check_types(se) 00225 except TypeError as te: self._check_types(te) 00226 00227 def deserialize_numpy(self, str, numpy): 00228 """ 00229 unpack serialized message in str into this message instance using numpy for array types 00230 @param str: byte array of serialized message 00231 @type str: str 00232 @param numpy: numpy python module 00233 @type numpy: module 00234 """ 00235 try: 00236 if self.mesh is None: 00237 self.mesh = arm_navigation_msgs.msg.Shape() 00238 end = 0 00239 _x = self 00240 start = end 00241 end += 5 00242 (_x.objectId, _x.mesh.type,) = _struct_ib.unpack(str[start:end]) 00243 start = end 00244 end += 4 00245 (length,) = _struct_I.unpack(str[start:end]) 00246 pattern = '<%sd'%length 00247 start = end 00248 end += struct.calcsize(pattern) 00249 self.mesh.dimensions = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00250 start = end 00251 end += 4 00252 (length,) = _struct_I.unpack(str[start:end]) 00253 pattern = '<%si'%length 00254 start = end 00255 end += struct.calcsize(pattern) 00256 self.mesh.triangles = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length) 00257 start = end 00258 end += 4 00259 (length,) = _struct_I.unpack(str[start:end]) 00260 self.mesh.vertices = [] 00261 for i in range(0, length): 00262 val1 = geometry_msgs.msg.Point() 00263 _x = val1 00264 start = end 00265 end += 24 00266 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end]) 00267 self.mesh.vertices.append(val1) 00268 start = end 00269 end += 4 00270 (length,) = _struct_I.unpack(str[start:end]) 00271 start = end 00272 end += length 00273 self.type = str[start:end] 00274 start = end 00275 end += 4 00276 (length,) = _struct_I.unpack(str[start:end]) 00277 start = end 00278 end += length 00279 self.data = str[start:end] 00280 return self 00281 except struct.error as e: 00282 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00283 00284 _struct_I = roslib.message.struct_I 00285 _struct_ib = struct.Struct("<ib") 00286 _struct_3d = struct.Struct("<3d")