00001 """autogenerated by genmsg_py from Int8MultiArray.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import std_msgs.msg
00006
00007 class Int8MultiArray(roslib.message.Message):
00008 _md5sum = "d7c1af35a1b4781bbe79e03dd94b7c13"
00009 _type = "std_msgs/Int8MultiArray"
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 int8[] 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','int8[]']
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(Int8MultiArray, 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 length = len(self.data)
00103 buff.write(_struct_I.pack(length))
00104 pattern = '<%sb'%length
00105 buff.write(struct.pack(pattern, *self.data))
00106 except struct.error as se: self._check_types(se)
00107 except TypeError as te: self._check_types(te)
00108
00109 def deserialize(self, str):
00110 """
00111 unpack serialized message in str into this message instance
00112 @param str: byte array of serialized message
00113 @type str: str
00114 """
00115 try:
00116 if self.layout is None:
00117 self.layout = std_msgs.msg.MultiArrayLayout()
00118 end = 0
00119 start = end
00120 end += 4
00121 (length,) = _struct_I.unpack(str[start:end])
00122 self.layout.dim = []
00123 for i in range(0, length):
00124 val1 = std_msgs.msg.MultiArrayDimension()
00125 start = end
00126 end += 4
00127 (length,) = _struct_I.unpack(str[start:end])
00128 start = end
00129 end += length
00130 val1.label = str[start:end]
00131 _x = val1
00132 start = end
00133 end += 8
00134 (_x.size, _x.stride,) = _struct_2I.unpack(str[start:end])
00135 self.layout.dim.append(val1)
00136 start = end
00137 end += 4
00138 (self.layout.data_offset,) = _struct_I.unpack(str[start:end])
00139 start = end
00140 end += 4
00141 (length,) = _struct_I.unpack(str[start:end])
00142 pattern = '<%sb'%length
00143 start = end
00144 end += struct.calcsize(pattern)
00145 self.data = struct.unpack(pattern, str[start:end])
00146 return self
00147 except struct.error as e:
00148 raise roslib.message.DeserializationError(e)
00149
00150
00151 def serialize_numpy(self, buff, numpy):
00152 """
00153 serialize message with numpy array types into buffer
00154 @param buff: buffer
00155 @type buff: StringIO
00156 @param numpy: numpy python module
00157 @type numpy module
00158 """
00159 try:
00160 length = len(self.layout.dim)
00161 buff.write(_struct_I.pack(length))
00162 for val1 in self.layout.dim:
00163 _x = val1.label
00164 length = len(_x)
00165 buff.write(struct.pack('<I%ss'%length, length, _x))
00166 _x = val1
00167 buff.write(_struct_2I.pack(_x.size, _x.stride))
00168 buff.write(_struct_I.pack(self.layout.data_offset))
00169 length = len(self.data)
00170 buff.write(_struct_I.pack(length))
00171 pattern = '<%sb'%length
00172 buff.write(self.data.tostring())
00173 except struct.error as se: self._check_types(se)
00174 except TypeError as te: self._check_types(te)
00175
00176 def deserialize_numpy(self, str, numpy):
00177 """
00178 unpack serialized message in str into this message instance using numpy for array types
00179 @param str: byte array of serialized message
00180 @type str: str
00181 @param numpy: numpy python module
00182 @type numpy: module
00183 """
00184 try:
00185 if self.layout is None:
00186 self.layout = std_msgs.msg.MultiArrayLayout()
00187 end = 0
00188 start = end
00189 end += 4
00190 (length,) = _struct_I.unpack(str[start:end])
00191 self.layout.dim = []
00192 for i in range(0, length):
00193 val1 = std_msgs.msg.MultiArrayDimension()
00194 start = end
00195 end += 4
00196 (length,) = _struct_I.unpack(str[start:end])
00197 start = end
00198 end += length
00199 val1.label = str[start:end]
00200 _x = val1
00201 start = end
00202 end += 8
00203 (_x.size, _x.stride,) = _struct_2I.unpack(str[start:end])
00204 self.layout.dim.append(val1)
00205 start = end
00206 end += 4
00207 (self.layout.data_offset,) = _struct_I.unpack(str[start:end])
00208 start = end
00209 end += 4
00210 (length,) = _struct_I.unpack(str[start:end])
00211 pattern = '<%sb'%length
00212 start = end
00213 end += struct.calcsize(pattern)
00214 self.data = numpy.frombuffer(str[start:end], dtype=numpy.int8, count=length)
00215 return self
00216 except struct.error as e:
00217 raise roslib.message.DeserializationError(e)
00218
00219 _struct_I = roslib.message.struct_I
00220 _struct_2I = struct.Struct("<2I")