00001 """autogenerated by genmsg_py from TriangleMesh.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 TriangleMesh(roslib.message.Message):
00010 _md5sum = "2cd8125b80abf942af5656b65994fe56"
00011 _type = "triangle_mesh_msgs/TriangleMesh"
00012 _has_header = True
00013 _full_text = """Header header
00014 geometry_msgs/Point32[] points
00015 geometry_msgs/Point32[] normals
00016 float32[] intensities
00017 triangle_mesh_msgs/Triangle[] triangles
00018 string sending_node
00019
00020 ================================================================================
00021 MSG: std_msgs/Header
00022 # Standard metadata for higher-level stamped data types.
00023 # This is generally used to communicate timestamped data
00024 # in a particular coordinate frame.
00025 #
00026 # sequence ID: consecutively increasing ID
00027 uint32 seq
00028 #Two-integer timestamp that is expressed as:
00029 # * stamp.secs: seconds (stamp_secs) since epoch
00030 # * stamp.nsecs: nanoseconds since stamp_secs
00031 # time-handling sugar is provided by the client library
00032 time stamp
00033 #Frame this data is associated with
00034 # 0: no frame
00035 # 1: global frame
00036 string frame_id
00037
00038 ================================================================================
00039 MSG: geometry_msgs/Point32
00040 # This contains the position of a point in free space(with 32 bits of precision).
00041 # It is recommeded to use Point wherever possible instead of Point32.
00042 #
00043 # This recommendation is to promote interoperability.
00044 #
00045 # This message is designed to take up less space when sending
00046 # lots of points at once, as in the case of a PointCloud.
00047
00048 float32 x
00049 float32 y
00050 float32 z
00051 ================================================================================
00052 MSG: triangle_mesh_msgs/Triangle
00053 int32 i
00054 int32 j
00055 int32 k
00056
00057
00058
00059 """
00060 __slots__ = ['header','points','normals','intensities','triangles','sending_node']
00061 _slot_types = ['Header','geometry_msgs/Point32[]','geometry_msgs/Point32[]','float32[]','triangle_mesh_msgs/Triangle[]','string']
00062
00063 def __init__(self, *args, **kwds):
00064 """
00065 Constructor. Any message fields that are implicitly/explicitly
00066 set to None will be assigned a default value. The recommend
00067 use is keyword arguments as this is more robust to future message
00068 changes. You cannot mix in-order arguments and keyword arguments.
00069
00070 The available fields are:
00071 header,points,normals,intensities,triangles,sending_node
00072
00073 @param args: complete set of field values, in .msg order
00074 @param kwds: use keyword arguments corresponding to message field names
00075 to set specific fields.
00076 """
00077 if args or kwds:
00078 super(TriangleMesh, self).__init__(*args, **kwds)
00079
00080 if self.header is None:
00081 self.header = std_msgs.msg._Header.Header()
00082 if self.points is None:
00083 self.points = []
00084 if self.normals is None:
00085 self.normals = []
00086 if self.intensities is None:
00087 self.intensities = []
00088 if self.triangles is None:
00089 self.triangles = []
00090 if self.sending_node is None:
00091 self.sending_node = ''
00092 else:
00093 self.header = std_msgs.msg._Header.Header()
00094 self.points = []
00095 self.normals = []
00096 self.intensities = []
00097 self.triangles = []
00098 self.sending_node = ''
00099
00100 def _get_types(self):
00101 """
00102 internal API method
00103 """
00104 return self._slot_types
00105
00106 def serialize(self, buff):
00107 """
00108 serialize message into buffer
00109 @param buff: buffer
00110 @type buff: StringIO
00111 """
00112 try:
00113 _x = self
00114 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00115 _x = self.header.frame_id
00116 length = len(_x)
00117 buff.write(struct.pack('<I%ss'%length, length, _x))
00118 length = len(self.points)
00119 buff.write(_struct_I.pack(length))
00120 for val1 in self.points:
00121 _x = val1
00122 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00123 length = len(self.normals)
00124 buff.write(_struct_I.pack(length))
00125 for val1 in self.normals:
00126 _x = val1
00127 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00128 length = len(self.intensities)
00129 buff.write(_struct_I.pack(length))
00130 pattern = '<%sf'%length
00131 buff.write(struct.pack(pattern, *self.intensities))
00132 length = len(self.triangles)
00133 buff.write(_struct_I.pack(length))
00134 for val1 in self.triangles:
00135 _x = val1
00136 buff.write(_struct_3i.pack(_x.i, _x.j, _x.k))
00137 _x = self.sending_node
00138 length = len(_x)
00139 buff.write(struct.pack('<I%ss'%length, length, _x))
00140 except struct.error, se: self._check_types(se)
00141 except TypeError, te: self._check_types(te)
00142
00143 def deserialize(self, str):
00144 """
00145 unpack serialized message in str into this message instance
00146 @param str: byte array of serialized message
00147 @type str: str
00148 """
00149 try:
00150 if self.header is None:
00151 self.header = std_msgs.msg._Header.Header()
00152 end = 0
00153 _x = self
00154 start = end
00155 end += 12
00156 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00157 start = end
00158 end += 4
00159 (length,) = _struct_I.unpack(str[start:end])
00160 start = end
00161 end += length
00162 self.header.frame_id = str[start:end]
00163 start = end
00164 end += 4
00165 (length,) = _struct_I.unpack(str[start:end])
00166 self.points = []
00167 for i in xrange(0, length):
00168 val1 = geometry_msgs.msg.Point32()
00169 _x = val1
00170 start = end
00171 end += 12
00172 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00173 self.points.append(val1)
00174 start = end
00175 end += 4
00176 (length,) = _struct_I.unpack(str[start:end])
00177 self.normals = []
00178 for i in xrange(0, length):
00179 val1 = geometry_msgs.msg.Point32()
00180 _x = val1
00181 start = end
00182 end += 12
00183 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00184 self.normals.append(val1)
00185 start = end
00186 end += 4
00187 (length,) = _struct_I.unpack(str[start:end])
00188 pattern = '<%sf'%length
00189 start = end
00190 end += struct.calcsize(pattern)
00191 self.intensities = struct.unpack(pattern, str[start:end])
00192 start = end
00193 end += 4
00194 (length,) = _struct_I.unpack(str[start:end])
00195 self.triangles = []
00196 for i in xrange(0, length):
00197 val1 = triangle_mesh_msgs.msg.Triangle()
00198 _x = val1
00199 start = end
00200 end += 12
00201 (_x.i, _x.j, _x.k,) = _struct_3i.unpack(str[start:end])
00202 self.triangles.append(val1)
00203 start = end
00204 end += 4
00205 (length,) = _struct_I.unpack(str[start:end])
00206 start = end
00207 end += length
00208 self.sending_node = str[start:end]
00209 return self
00210 except struct.error, e:
00211 raise roslib.message.DeserializationError(e)
00212
00213
00214 def serialize_numpy(self, buff, numpy):
00215 """
00216 serialize message with numpy array types into buffer
00217 @param buff: buffer
00218 @type buff: StringIO
00219 @param numpy: numpy python module
00220 @type numpy module
00221 """
00222 try:
00223 _x = self
00224 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00225 _x = self.header.frame_id
00226 length = len(_x)
00227 buff.write(struct.pack('<I%ss'%length, length, _x))
00228 length = len(self.points)
00229 buff.write(_struct_I.pack(length))
00230 for val1 in self.points:
00231 _x = val1
00232 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00233 length = len(self.normals)
00234 buff.write(_struct_I.pack(length))
00235 for val1 in self.normals:
00236 _x = val1
00237 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00238 length = len(self.intensities)
00239 buff.write(_struct_I.pack(length))
00240 pattern = '<%sf'%length
00241 buff.write(self.intensities.tostring())
00242 length = len(self.triangles)
00243 buff.write(_struct_I.pack(length))
00244 for val1 in self.triangles:
00245 _x = val1
00246 buff.write(_struct_3i.pack(_x.i, _x.j, _x.k))
00247 _x = self.sending_node
00248 length = len(_x)
00249 buff.write(struct.pack('<I%ss'%length, length, _x))
00250 except struct.error, se: self._check_types(se)
00251 except TypeError, te: self._check_types(te)
00252
00253 def deserialize_numpy(self, str, numpy):
00254 """
00255 unpack serialized message in str into this message instance using numpy for array types
00256 @param str: byte array of serialized message
00257 @type str: str
00258 @param numpy: numpy python module
00259 @type numpy: module
00260 """
00261 try:
00262 if self.header is None:
00263 self.header = std_msgs.msg._Header.Header()
00264 end = 0
00265 _x = self
00266 start = end
00267 end += 12
00268 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00269 start = end
00270 end += 4
00271 (length,) = _struct_I.unpack(str[start:end])
00272 start = end
00273 end += length
00274 self.header.frame_id = str[start:end]
00275 start = end
00276 end += 4
00277 (length,) = _struct_I.unpack(str[start:end])
00278 self.points = []
00279 for i in xrange(0, length):
00280 val1 = geometry_msgs.msg.Point32()
00281 _x = val1
00282 start = end
00283 end += 12
00284 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00285 self.points.append(val1)
00286 start = end
00287 end += 4
00288 (length,) = _struct_I.unpack(str[start:end])
00289 self.normals = []
00290 for i in xrange(0, length):
00291 val1 = geometry_msgs.msg.Point32()
00292 _x = val1
00293 start = end
00294 end += 12
00295 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00296 self.normals.append(val1)
00297 start = end
00298 end += 4
00299 (length,) = _struct_I.unpack(str[start:end])
00300 pattern = '<%sf'%length
00301 start = end
00302 end += struct.calcsize(pattern)
00303 self.intensities = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00304 start = end
00305 end += 4
00306 (length,) = _struct_I.unpack(str[start:end])
00307 self.triangles = []
00308 for i in xrange(0, length):
00309 val1 = triangle_mesh_msgs.msg.Triangle()
00310 _x = val1
00311 start = end
00312 end += 12
00313 (_x.i, _x.j, _x.k,) = _struct_3i.unpack(str[start:end])
00314 self.triangles.append(val1)
00315 start = end
00316 end += 4
00317 (length,) = _struct_I.unpack(str[start:end])
00318 start = end
00319 end += length
00320 self.sending_node = str[start:end]
00321 return self
00322 except struct.error, e:
00323 raise roslib.message.DeserializationError(e)
00324
00325 _struct_I = roslib.message.struct_I
00326 _struct_3I = struct.Struct("<3I")
00327 _struct_3f = struct.Struct("<3f")
00328 _struct_3i = struct.Struct("<3i")