00001 """autogenerated by genmsg_py from TriangleMeshToNameRequest.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import geometry_msgs.msg
00006 import triangle_mesh_msgs.msg
00007 import std_msgs.msg
00008
00009 class TriangleMeshToNameRequest(roslib.message.Message):
00010 _md5sum = "c9fa2982cc45237506b1b8c8a4d4623c"
00011 _type = "annotation_srvs/TriangleMeshToNameRequest"
00012 _has_header = False
00013 _full_text = """
00014
00015 triangle_mesh_msgs/TriangleMesh mesh
00016
00017 ================================================================================
00018 MSG: triangle_mesh_msgs/TriangleMesh
00019 Header header
00020 geometry_msgs/Point32[] points
00021 geometry_msgs/Point32[] normals
00022 float32[] intensities
00023 triangle_mesh_msgs/Triangle[] triangles
00024 string sending_node
00025
00026 ================================================================================
00027 MSG: std_msgs/Header
00028 # Standard metadata for higher-level stamped data types.
00029 # This is generally used to communicate timestamped data
00030 # in a particular coordinate frame.
00031 #
00032 # sequence ID: consecutively increasing ID
00033 uint32 seq
00034 #Two-integer timestamp that is expressed as:
00035 # * stamp.secs: seconds (stamp_secs) since epoch
00036 # * stamp.nsecs: nanoseconds since stamp_secs
00037 # time-handling sugar is provided by the client library
00038 time stamp
00039 #Frame this data is associated with
00040 # 0: no frame
00041 # 1: global frame
00042 string frame_id
00043
00044 ================================================================================
00045 MSG: geometry_msgs/Point32
00046 # This contains the position of a point in free space(with 32 bits of precision).
00047 # It is recommeded to use Point wherever possible instead of Point32.
00048 #
00049 # This recommendation is to promote interoperability.
00050 #
00051 # This message is designed to take up less space when sending
00052 # lots of points at once, as in the case of a PointCloud.
00053
00054 float32 x
00055 float32 y
00056 float32 z
00057 ================================================================================
00058 MSG: triangle_mesh_msgs/Triangle
00059 int32 i
00060 int32 j
00061 int32 k
00062
00063
00064
00065 """
00066 __slots__ = ['mesh']
00067 _slot_types = ['triangle_mesh_msgs/TriangleMesh']
00068
00069 def __init__(self, *args, **kwds):
00070 """
00071 Constructor. Any message fields that are implicitly/explicitly
00072 set to None will be assigned a default value. The recommend
00073 use is keyword arguments as this is more robust to future message
00074 changes. You cannot mix in-order arguments and keyword arguments.
00075
00076 The available fields are:
00077 mesh
00078
00079 @param args: complete set of field values, in .msg order
00080 @param kwds: use keyword arguments corresponding to message field names
00081 to set specific fields.
00082 """
00083 if args or kwds:
00084 super(TriangleMeshToNameRequest, self).__init__(*args, **kwds)
00085
00086 if self.mesh is None:
00087 self.mesh = triangle_mesh_msgs.msg.TriangleMesh()
00088 else:
00089 self.mesh = triangle_mesh_msgs.msg.TriangleMesh()
00090
00091 def _get_types(self):
00092 """
00093 internal API method
00094 """
00095 return self._slot_types
00096
00097 def serialize(self, buff):
00098 """
00099 serialize message into buffer
00100 @param buff: buffer
00101 @type buff: StringIO
00102 """
00103 try:
00104 _x = self
00105 buff.write(_struct_3I.pack(_x.mesh.header.seq, _x.mesh.header.stamp.secs, _x.mesh.header.stamp.nsecs))
00106 _x = self.mesh.header.frame_id
00107 length = len(_x)
00108 buff.write(struct.pack('<I%ss'%length, length, _x))
00109 length = len(self.mesh.points)
00110 buff.write(_struct_I.pack(length))
00111 for val1 in self.mesh.points:
00112 _x = val1
00113 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00114 length = len(self.mesh.normals)
00115 buff.write(_struct_I.pack(length))
00116 for val1 in self.mesh.normals:
00117 _x = val1
00118 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00119 length = len(self.mesh.intensities)
00120 buff.write(_struct_I.pack(length))
00121 pattern = '<%sf'%length
00122 buff.write(struct.pack(pattern, *self.mesh.intensities))
00123 length = len(self.mesh.triangles)
00124 buff.write(_struct_I.pack(length))
00125 for val1 in self.mesh.triangles:
00126 _x = val1
00127 buff.write(_struct_3i.pack(_x.i, _x.j, _x.k))
00128 _x = self.mesh.sending_node
00129 length = len(_x)
00130 buff.write(struct.pack('<I%ss'%length, length, _x))
00131 except struct.error, se: self._check_types(se)
00132 except TypeError, 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 = triangle_mesh_msgs.msg.TriangleMesh()
00143 end = 0
00144 _x = self
00145 start = end
00146 end += 12
00147 (_x.mesh.header.seq, _x.mesh.header.stamp.secs, _x.mesh.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00148 start = end
00149 end += 4
00150 (length,) = _struct_I.unpack(str[start:end])
00151 start = end
00152 end += length
00153 self.mesh.header.frame_id = str[start:end]
00154 start = end
00155 end += 4
00156 (length,) = _struct_I.unpack(str[start:end])
00157 self.mesh.points = []
00158 for i in xrange(0, length):
00159 val1 = geometry_msgs.msg.Point32()
00160 _x = val1
00161 start = end
00162 end += 12
00163 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00164 self.mesh.points.append(val1)
00165 start = end
00166 end += 4
00167 (length,) = _struct_I.unpack(str[start:end])
00168 self.mesh.normals = []
00169 for i in xrange(0, length):
00170 val1 = geometry_msgs.msg.Point32()
00171 _x = val1
00172 start = end
00173 end += 12
00174 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00175 self.mesh.normals.append(val1)
00176 start = end
00177 end += 4
00178 (length,) = _struct_I.unpack(str[start:end])
00179 pattern = '<%sf'%length
00180 start = end
00181 end += struct.calcsize(pattern)
00182 self.mesh.intensities = struct.unpack(pattern, str[start:end])
00183 start = end
00184 end += 4
00185 (length,) = _struct_I.unpack(str[start:end])
00186 self.mesh.triangles = []
00187 for i in xrange(0, length):
00188 val1 = triangle_mesh_msgs.msg.Triangle()
00189 _x = val1
00190 start = end
00191 end += 12
00192 (_x.i, _x.j, _x.k,) = _struct_3i.unpack(str[start:end])
00193 self.mesh.triangles.append(val1)
00194 start = end
00195 end += 4
00196 (length,) = _struct_I.unpack(str[start:end])
00197 start = end
00198 end += length
00199 self.mesh.sending_node = str[start:end]
00200 return self
00201 except struct.error, e:
00202 raise roslib.message.DeserializationError(e)
00203
00204
00205 def serialize_numpy(self, buff, numpy):
00206 """
00207 serialize message with numpy array types into buffer
00208 @param buff: buffer
00209 @type buff: StringIO
00210 @param numpy: numpy python module
00211 @type numpy module
00212 """
00213 try:
00214 _x = self
00215 buff.write(_struct_3I.pack(_x.mesh.header.seq, _x.mesh.header.stamp.secs, _x.mesh.header.stamp.nsecs))
00216 _x = self.mesh.header.frame_id
00217 length = len(_x)
00218 buff.write(struct.pack('<I%ss'%length, length, _x))
00219 length = len(self.mesh.points)
00220 buff.write(_struct_I.pack(length))
00221 for val1 in self.mesh.points:
00222 _x = val1
00223 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00224 length = len(self.mesh.normals)
00225 buff.write(_struct_I.pack(length))
00226 for val1 in self.mesh.normals:
00227 _x = val1
00228 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00229 length = len(self.mesh.intensities)
00230 buff.write(_struct_I.pack(length))
00231 pattern = '<%sf'%length
00232 buff.write(self.mesh.intensities.tostring())
00233 length = len(self.mesh.triangles)
00234 buff.write(_struct_I.pack(length))
00235 for val1 in self.mesh.triangles:
00236 _x = val1
00237 buff.write(_struct_3i.pack(_x.i, _x.j, _x.k))
00238 _x = self.mesh.sending_node
00239 length = len(_x)
00240 buff.write(struct.pack('<I%ss'%length, length, _x))
00241 except struct.error, se: self._check_types(se)
00242 except TypeError, te: self._check_types(te)
00243
00244 def deserialize_numpy(self, str, numpy):
00245 """
00246 unpack serialized message in str into this message instance using numpy for array types
00247 @param str: byte array of serialized message
00248 @type str: str
00249 @param numpy: numpy python module
00250 @type numpy: module
00251 """
00252 try:
00253 if self.mesh is None:
00254 self.mesh = triangle_mesh_msgs.msg.TriangleMesh()
00255 end = 0
00256 _x = self
00257 start = end
00258 end += 12
00259 (_x.mesh.header.seq, _x.mesh.header.stamp.secs, _x.mesh.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00260 start = end
00261 end += 4
00262 (length,) = _struct_I.unpack(str[start:end])
00263 start = end
00264 end += length
00265 self.mesh.header.frame_id = str[start:end]
00266 start = end
00267 end += 4
00268 (length,) = _struct_I.unpack(str[start:end])
00269 self.mesh.points = []
00270 for i in xrange(0, length):
00271 val1 = geometry_msgs.msg.Point32()
00272 _x = val1
00273 start = end
00274 end += 12
00275 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00276 self.mesh.points.append(val1)
00277 start = end
00278 end += 4
00279 (length,) = _struct_I.unpack(str[start:end])
00280 self.mesh.normals = []
00281 for i in xrange(0, length):
00282 val1 = geometry_msgs.msg.Point32()
00283 _x = val1
00284 start = end
00285 end += 12
00286 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00287 self.mesh.normals.append(val1)
00288 start = end
00289 end += 4
00290 (length,) = _struct_I.unpack(str[start:end])
00291 pattern = '<%sf'%length
00292 start = end
00293 end += struct.calcsize(pattern)
00294 self.mesh.intensities = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00295 start = end
00296 end += 4
00297 (length,) = _struct_I.unpack(str[start:end])
00298 self.mesh.triangles = []
00299 for i in xrange(0, length):
00300 val1 = triangle_mesh_msgs.msg.Triangle()
00301 _x = val1
00302 start = end
00303 end += 12
00304 (_x.i, _x.j, _x.k,) = _struct_3i.unpack(str[start:end])
00305 self.mesh.triangles.append(val1)
00306 start = end
00307 end += 4
00308 (length,) = _struct_I.unpack(str[start:end])
00309 start = end
00310 end += length
00311 self.mesh.sending_node = str[start:end]
00312 return self
00313 except struct.error, e:
00314 raise roslib.message.DeserializationError(e)
00315
00316 _struct_I = roslib.message.struct_I
00317 _struct_3I = struct.Struct("<3I")
00318 _struct_3f = struct.Struct("<3f")
00319 _struct_3i = struct.Struct("<3i")
00320 """autogenerated by genmsg_py from TriangleMeshToNameResponse.msg. Do not edit."""
00321 import roslib.message
00322 import struct
00323
00324
00325 class TriangleMeshToNameResponse(roslib.message.Message):
00326 _md5sum = "c1f3d28f1b044c871e6eff2e9fc3c667"
00327 _type = "annotation_srvs/TriangleMeshToNameResponse"
00328 _has_header = False
00329 _full_text = """string name
00330
00331 """
00332 __slots__ = ['name']
00333 _slot_types = ['string']
00334
00335 def __init__(self, *args, **kwds):
00336 """
00337 Constructor. Any message fields that are implicitly/explicitly
00338 set to None will be assigned a default value. The recommend
00339 use is keyword arguments as this is more robust to future message
00340 changes. You cannot mix in-order arguments and keyword arguments.
00341
00342 The available fields are:
00343 name
00344
00345 @param args: complete set of field values, in .msg order
00346 @param kwds: use keyword arguments corresponding to message field names
00347 to set specific fields.
00348 """
00349 if args or kwds:
00350 super(TriangleMeshToNameResponse, self).__init__(*args, **kwds)
00351
00352 if self.name is None:
00353 self.name = ''
00354 else:
00355 self.name = ''
00356
00357 def _get_types(self):
00358 """
00359 internal API method
00360 """
00361 return self._slot_types
00362
00363 def serialize(self, buff):
00364 """
00365 serialize message into buffer
00366 @param buff: buffer
00367 @type buff: StringIO
00368 """
00369 try:
00370 _x = self.name
00371 length = len(_x)
00372 buff.write(struct.pack('<I%ss'%length, length, _x))
00373 except struct.error, se: self._check_types(se)
00374 except TypeError, te: self._check_types(te)
00375
00376 def deserialize(self, str):
00377 """
00378 unpack serialized message in str into this message instance
00379 @param str: byte array of serialized message
00380 @type str: str
00381 """
00382 try:
00383 end = 0
00384 start = end
00385 end += 4
00386 (length,) = _struct_I.unpack(str[start:end])
00387 start = end
00388 end += length
00389 self.name = str[start:end]
00390 return self
00391 except struct.error, e:
00392 raise roslib.message.DeserializationError(e)
00393
00394
00395 def serialize_numpy(self, buff, numpy):
00396 """
00397 serialize message with numpy array types into buffer
00398 @param buff: buffer
00399 @type buff: StringIO
00400 @param numpy: numpy python module
00401 @type numpy module
00402 """
00403 try:
00404 _x = self.name
00405 length = len(_x)
00406 buff.write(struct.pack('<I%ss'%length, length, _x))
00407 except struct.error, se: self._check_types(se)
00408 except TypeError, te: self._check_types(te)
00409
00410 def deserialize_numpy(self, str, numpy):
00411 """
00412 unpack serialized message in str into this message instance using numpy for array types
00413 @param str: byte array of serialized message
00414 @type str: str
00415 @param numpy: numpy python module
00416 @type numpy: module
00417 """
00418 try:
00419 end = 0
00420 start = end
00421 end += 4
00422 (length,) = _struct_I.unpack(str[start:end])
00423 start = end
00424 end += length
00425 self.name = str[start:end]
00426 return self
00427 except struct.error, e:
00428 raise roslib.message.DeserializationError(e)
00429
00430 _struct_I = roslib.message.struct_I
00431 class TriangleMeshToName(roslib.message.ServiceDefinition):
00432 _type = 'annotation_srvs/TriangleMeshToName'
00433 _md5sum = '962f6681d8f3f343ad5f5edeffbd3870'
00434 _request_class = TriangleMeshToNameRequest
00435 _response_class = TriangleMeshToNameResponse