00001 """autogenerated by genmsg_py from UInt8MultiArray.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import std_msgs.msg
00006
00007 class UInt8MultiArray(roslib.message.Message):
00008 _md5sum = "82373f1612381bb6ee473b5cd6f5d89c"
00009 _type = "std_msgs/UInt8MultiArray"
00010 _has_header = False
00011 _full_text = """# Please look at the MultiArrayLayout message definition for
00012 # documentation on all multiarrays.
00013
00014 MultiArrayLayout layout # specification of data layout
00015 uint8[] data # array of data
00016
00017
00018 ================================================================================
00019 MSG: std_msgs/MultiArrayLayout
00020 # The multiarray declares a generic multi-dimensional array of a
00021 # particular data type. Dimensions are ordered from outer most
00022 # to inner most.
00023
00024 MultiArrayDimension[] dim # Array of dimension properties
00025 uint32 data_offset # padding bytes at front of data
00026
00027 # Accessors should ALWAYS be written in terms of dimension stride
00028 # and specified outer-most dimension first.
00029 #
00030 # multiarray(i,j,k) = data[data_offset + dim_stride[1]*i + dim_stride[2]*j + k]
00031 #
00032 # A standard, 3-channel 640x480 image with interleaved color channels
00033 # would be specified as:
00034 #
00035 # dim[0].label = "height"
00036 # dim[0].size = 480
00037 # dim[0].stride = 3*640*480 = 921600 (note dim[0] stride is just size of image)
00038 # dim[1].label = "width"
00039 # dim[1].size = 640
00040 # dim[1].stride = 3*640 = 1920
00041 # dim[2].label = "channel"
00042 # dim[2].size = 3
00043 # dim[2].stride = 3
00044 #
00045 # multiarray(i,j,k) refers to the ith row, jth column, and kth channel.
00046 ================================================================================
00047 MSG: std_msgs/MultiArrayDimension
00048 string label # label of given dimension
00049 uint32 size # size of given dimension (in type units)
00050 uint32 stride # stride of given dimension
00051 """
00052 __slots__ = ['layout','data']
00053 _slot_types = ['std_msgs/MultiArrayLayout','uint8[]']
00054
00055 def __init__(self, *args, **kwds):
00056 """
00057 Constructor. Any message fields that are implicitly/explicitly
00058 set to None will be assigned a default value. The recommend
00059 use is keyword arguments as this is more robust to future message
00060 changes. You cannot mix in-order arguments and keyword arguments.
00061
00062 The available fields are:
00063 layout,data
00064
00065 @param args: complete set of field values, in .msg order
00066 @param kwds: use keyword arguments corresponding to message field names
00067 to set specific fields.
00068 """
00069 if args or kwds:
00070 super(UInt8MultiArray, self).__init__(*args, **kwds)
00071
00072 if self.layout is None:
00073 self.layout = std_msgs.msg.MultiArrayLayout()
00074 if self.data is None:
00075 self.data = ''
00076 else:
00077 self.layout = std_msgs.msg.MultiArrayLayout()
00078 self.data = ''
00079
00080 def _get_types(self):
00081 """
00082 internal API method
00083 """
00084 return self._slot_types
00085
00086 def serialize(self, buff):
00087 """
00088 serialize message into buffer
00089 @param buff: buffer
00090 @type buff: StringIO
00091 """
00092 try:
00093 length = len(self.layout.dim)
00094 buff.write(_struct_I.pack(length))
00095 for val1 in self.layout.dim:
00096 _x = val1.label
00097 length = len(_x)
00098 buff.write(struct.pack('<I%ss'%length, length, _x))
00099 _x = val1
00100 buff.write(_struct_2I.pack(_x.size, _x.stride))
00101 buff.write(_struct_I.pack(self.layout.data_offset))
00102 _x = self.data
00103 length = len(_x)
00104
00105 if type(_x) in [list, tuple]:
00106 buff.write(struct.pack('<I%sB'%length, length, *_x))
00107 else:
00108 buff.write(struct.pack('<I%ss'%length, length, _x))
00109 except struct.error as se: self._check_types(se)
00110 except TypeError as te: self._check_types(te)
00111
00112 def deserialize(self, str):
00113 """
00114 unpack serialized message in str into this message instance
00115 @param str: byte array of serialized message
00116 @type str: str
00117 """
00118 try:
00119 if self.layout is None:
00120 self.layout = std_msgs.msg.MultiArrayLayout()
00121 end = 0
00122 start = end
00123 end += 4
00124 (length,) = _struct_I.unpack(str[start:end])
00125 self.layout.dim = []
00126 for i in range(0, length):
00127 val1 = std_msgs.msg.MultiArrayDimension()
00128 start = end
00129 end += 4
00130 (length,) = _struct_I.unpack(str[start:end])
00131 start = end
00132 end += length
00133 val1.label = str[start:end]
00134 _x = val1
00135 start = end
00136 end += 8
00137 (_x.size, _x.stride,) = _struct_2I.unpack(str[start:end])
00138 self.layout.dim.append(val1)
00139 start = end
00140 end += 4
00141 (self.layout.data_offset,) = _struct_I.unpack(str[start:end])
00142 start = end
00143 end += 4
00144 (length,) = _struct_I.unpack(str[start:end])
00145 start = end
00146 end += length
00147 self.data = str[start:end]
00148 return self
00149 except struct.error as e:
00150 raise roslib.message.DeserializationError(e)
00151
00152
00153 def serialize_numpy(self, buff, numpy):
00154 """
00155 serialize message with numpy array types into buffer
00156 @param buff: buffer
00157 @type buff: StringIO
00158 @param numpy: numpy python module
00159 @type numpy module
00160 """
00161 try:
00162 length = len(self.layout.dim)
00163 buff.write(_struct_I.pack(length))
00164 for val1 in self.layout.dim:
00165 _x = val1.label
00166 length = len(_x)
00167 buff.write(struct.pack('<I%ss'%length, length, _x))
00168 _x = val1
00169 buff.write(_struct_2I.pack(_x.size, _x.stride))
00170 buff.write(_struct_I.pack(self.layout.data_offset))
00171 _x = self.data
00172 length = len(_x)
00173
00174 if type(_x) in [list, tuple]:
00175 buff.write(struct.pack('<I%sB'%length, length, *_x))
00176 else:
00177 buff.write(struct.pack('<I%ss'%length, length, _x))
00178 except struct.error as se: self._check_types(se)
00179 except TypeError as te: self._check_types(te)
00180
00181 def deserialize_numpy(self, str, numpy):
00182 """
00183 unpack serialized message in str into this message instance using numpy for array types
00184 @param str: byte array of serialized message
00185 @type str: str
00186 @param numpy: numpy python module
00187 @type numpy: module
00188 """
00189 try:
00190 if self.layout is None:
00191 self.layout = std_msgs.msg.MultiArrayLayout()
00192 end = 0
00193 start = end
00194 end += 4
00195 (length,) = _struct_I.unpack(str[start:end])
00196 self.layout.dim = []
00197 for i in range(0, length):
00198 val1 = std_msgs.msg.MultiArrayDimension()
00199 start = end
00200 end += 4
00201 (length,) = _struct_I.unpack(str[start:end])
00202 start = end
00203 end += length
00204 val1.label = str[start:end]
00205 _x = val1
00206 start = end
00207 end += 8
00208 (_x.size, _x.stride,) = _struct_2I.unpack(str[start:end])
00209 self.layout.dim.append(val1)
00210 start = end
00211 end += 4
00212 (self.layout.data_offset,) = _struct_I.unpack(str[start:end])
00213 start = end
00214 end += 4
00215 (length,) = _struct_I.unpack(str[start:end])
00216 start = end
00217 end += length
00218 self.data = str[start:end]
00219 return self
00220 except struct.error as e:
00221 raise roslib.message.DeserializationError(e)
00222
00223 _struct_I = roslib.message.struct_I
00224 _struct_2I = struct.Struct("<2I")