00001 """autogenerated by genpy from nasa_r2_common_msgs/LabeledGripperPositionCommand.msg. Do not edit."""
00002 import sys
00003 python3 = True if sys.hexversion > 0x03000000 else False
00004 import genpy
00005 import struct
00006
00007 import std_msgs.msg
00008
00009 class LabeledGripperPositionCommand(genpy.Message):
00010 _md5sum = "cdc758be1e885c351a0d055826094942"
00011 _type = "nasa_r2_common_msgs/LabeledGripperPositionCommand"
00012 _has_header = True
00013 _full_text = """Header header
00014 string originator
00015 string[] name
00016 string[] setpoint
00017 string[] command
00018 float64[] force
00019 uint16[] dutyCycle
00020
00021 ================================================================================
00022 MSG: std_msgs/Header
00023 # Standard metadata for higher-level stamped data types.
00024 # This is generally used to communicate timestamped data
00025 # in a particular coordinate frame.
00026 #
00027 # sequence ID: consecutively increasing ID
00028 uint32 seq
00029 #Two-integer timestamp that is expressed as:
00030 # * stamp.secs: seconds (stamp_secs) since epoch
00031 # * stamp.nsecs: nanoseconds since stamp_secs
00032 # time-handling sugar is provided by the client library
00033 time stamp
00034 #Frame this data is associated with
00035 # 0: no frame
00036 # 1: global frame
00037 string frame_id
00038
00039 """
00040 __slots__ = ['header','originator','name','setpoint','command','force','dutyCycle']
00041 _slot_types = ['std_msgs/Header','string','string[]','string[]','string[]','float64[]','uint16[]']
00042
00043 def __init__(self, *args, **kwds):
00044 """
00045 Constructor. Any message fields that are implicitly/explicitly
00046 set to None will be assigned a default value. The recommend
00047 use is keyword arguments as this is more robust to future message
00048 changes. You cannot mix in-order arguments and keyword arguments.
00049
00050 The available fields are:
00051 header,originator,name,setpoint,command,force,dutyCycle
00052
00053 :param args: complete set of field values, in .msg order
00054 :param kwds: use keyword arguments corresponding to message field names
00055 to set specific fields.
00056 """
00057 if args or kwds:
00058 super(LabeledGripperPositionCommand, self).__init__(*args, **kwds)
00059
00060 if self.header is None:
00061 self.header = std_msgs.msg.Header()
00062 if self.originator is None:
00063 self.originator = ''
00064 if self.name is None:
00065 self.name = []
00066 if self.setpoint is None:
00067 self.setpoint = []
00068 if self.command is None:
00069 self.command = []
00070 if self.force is None:
00071 self.force = []
00072 if self.dutyCycle is None:
00073 self.dutyCycle = []
00074 else:
00075 self.header = std_msgs.msg.Header()
00076 self.originator = ''
00077 self.name = []
00078 self.setpoint = []
00079 self.command = []
00080 self.force = []
00081 self.dutyCycle = []
00082
00083 def _get_types(self):
00084 """
00085 internal API method
00086 """
00087 return self._slot_types
00088
00089 def serialize(self, buff):
00090 """
00091 serialize message into buffer
00092 :param buff: buffer, ``StringIO``
00093 """
00094 try:
00095 _x = self
00096 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00097 _x = self.header.frame_id
00098 length = len(_x)
00099 if python3 or type(_x) == unicode:
00100 _x = _x.encode('utf-8')
00101 length = len(_x)
00102 buff.write(struct.pack('<I%ss'%length, length, _x))
00103 _x = self.originator
00104 length = len(_x)
00105 if python3 or type(_x) == unicode:
00106 _x = _x.encode('utf-8')
00107 length = len(_x)
00108 buff.write(struct.pack('<I%ss'%length, length, _x))
00109 length = len(self.name)
00110 buff.write(_struct_I.pack(length))
00111 for val1 in self.name:
00112 length = len(val1)
00113 if python3 or type(val1) == unicode:
00114 val1 = val1.encode('utf-8')
00115 length = len(val1)
00116 buff.write(struct.pack('<I%ss'%length, length, val1))
00117 length = len(self.setpoint)
00118 buff.write(_struct_I.pack(length))
00119 for val1 in self.setpoint:
00120 length = len(val1)
00121 if python3 or type(val1) == unicode:
00122 val1 = val1.encode('utf-8')
00123 length = len(val1)
00124 buff.write(struct.pack('<I%ss'%length, length, val1))
00125 length = len(self.command)
00126 buff.write(_struct_I.pack(length))
00127 for val1 in self.command:
00128 length = len(val1)
00129 if python3 or type(val1) == unicode:
00130 val1 = val1.encode('utf-8')
00131 length = len(val1)
00132 buff.write(struct.pack('<I%ss'%length, length, val1))
00133 length = len(self.force)
00134 buff.write(_struct_I.pack(length))
00135 pattern = '<%sd'%length
00136 buff.write(struct.pack(pattern, *self.force))
00137 length = len(self.dutyCycle)
00138 buff.write(_struct_I.pack(length))
00139 pattern = '<%sH'%length
00140 buff.write(struct.pack(pattern, *self.dutyCycle))
00141 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00142 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00143
00144 def deserialize(self, str):
00145 """
00146 unpack serialized message in str into this message instance
00147 :param str: byte array of serialized message, ``str``
00148 """
00149 try:
00150 if self.header is None:
00151 self.header = std_msgs.msg.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 if python3:
00163 self.header.frame_id = str[start:end].decode('utf-8')
00164 else:
00165 self.header.frame_id = str[start:end]
00166 start = end
00167 end += 4
00168 (length,) = _struct_I.unpack(str[start:end])
00169 start = end
00170 end += length
00171 if python3:
00172 self.originator = str[start:end].decode('utf-8')
00173 else:
00174 self.originator = str[start:end]
00175 start = end
00176 end += 4
00177 (length,) = _struct_I.unpack(str[start:end])
00178 self.name = []
00179 for i in range(0, length):
00180 start = end
00181 end += 4
00182 (length,) = _struct_I.unpack(str[start:end])
00183 start = end
00184 end += length
00185 if python3:
00186 val1 = str[start:end].decode('utf-8')
00187 else:
00188 val1 = str[start:end]
00189 self.name.append(val1)
00190 start = end
00191 end += 4
00192 (length,) = _struct_I.unpack(str[start:end])
00193 self.setpoint = []
00194 for i in range(0, length):
00195 start = end
00196 end += 4
00197 (length,) = _struct_I.unpack(str[start:end])
00198 start = end
00199 end += length
00200 if python3:
00201 val1 = str[start:end].decode('utf-8')
00202 else:
00203 val1 = str[start:end]
00204 self.setpoint.append(val1)
00205 start = end
00206 end += 4
00207 (length,) = _struct_I.unpack(str[start:end])
00208 self.command = []
00209 for i in range(0, length):
00210 start = end
00211 end += 4
00212 (length,) = _struct_I.unpack(str[start:end])
00213 start = end
00214 end += length
00215 if python3:
00216 val1 = str[start:end].decode('utf-8')
00217 else:
00218 val1 = str[start:end]
00219 self.command.append(val1)
00220 start = end
00221 end += 4
00222 (length,) = _struct_I.unpack(str[start:end])
00223 pattern = '<%sd'%length
00224 start = end
00225 end += struct.calcsize(pattern)
00226 self.force = struct.unpack(pattern, str[start:end])
00227 start = end
00228 end += 4
00229 (length,) = _struct_I.unpack(str[start:end])
00230 pattern = '<%sH'%length
00231 start = end
00232 end += struct.calcsize(pattern)
00233 self.dutyCycle = struct.unpack(pattern, str[start:end])
00234 return self
00235 except struct.error as e:
00236 raise genpy.DeserializationError(e)
00237
00238
00239 def serialize_numpy(self, buff, numpy):
00240 """
00241 serialize message with numpy array types into buffer
00242 :param buff: buffer, ``StringIO``
00243 :param numpy: numpy python module
00244 """
00245 try:
00246 _x = self
00247 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00248 _x = self.header.frame_id
00249 length = len(_x)
00250 if python3 or type(_x) == unicode:
00251 _x = _x.encode('utf-8')
00252 length = len(_x)
00253 buff.write(struct.pack('<I%ss'%length, length, _x))
00254 _x = self.originator
00255 length = len(_x)
00256 if python3 or type(_x) == unicode:
00257 _x = _x.encode('utf-8')
00258 length = len(_x)
00259 buff.write(struct.pack('<I%ss'%length, length, _x))
00260 length = len(self.name)
00261 buff.write(_struct_I.pack(length))
00262 for val1 in self.name:
00263 length = len(val1)
00264 if python3 or type(val1) == unicode:
00265 val1 = val1.encode('utf-8')
00266 length = len(val1)
00267 buff.write(struct.pack('<I%ss'%length, length, val1))
00268 length = len(self.setpoint)
00269 buff.write(_struct_I.pack(length))
00270 for val1 in self.setpoint:
00271 length = len(val1)
00272 if python3 or type(val1) == unicode:
00273 val1 = val1.encode('utf-8')
00274 length = len(val1)
00275 buff.write(struct.pack('<I%ss'%length, length, val1))
00276 length = len(self.command)
00277 buff.write(_struct_I.pack(length))
00278 for val1 in self.command:
00279 length = len(val1)
00280 if python3 or type(val1) == unicode:
00281 val1 = val1.encode('utf-8')
00282 length = len(val1)
00283 buff.write(struct.pack('<I%ss'%length, length, val1))
00284 length = len(self.force)
00285 buff.write(_struct_I.pack(length))
00286 pattern = '<%sd'%length
00287 buff.write(self.force.tostring())
00288 length = len(self.dutyCycle)
00289 buff.write(_struct_I.pack(length))
00290 pattern = '<%sH'%length
00291 buff.write(self.dutyCycle.tostring())
00292 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00293 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00294
00295 def deserialize_numpy(self, str, numpy):
00296 """
00297 unpack serialized message in str into this message instance using numpy for array types
00298 :param str: byte array of serialized message, ``str``
00299 :param numpy: numpy python module
00300 """
00301 try:
00302 if self.header is None:
00303 self.header = std_msgs.msg.Header()
00304 end = 0
00305 _x = self
00306 start = end
00307 end += 12
00308 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00309 start = end
00310 end += 4
00311 (length,) = _struct_I.unpack(str[start:end])
00312 start = end
00313 end += length
00314 if python3:
00315 self.header.frame_id = str[start:end].decode('utf-8')
00316 else:
00317 self.header.frame_id = str[start:end]
00318 start = end
00319 end += 4
00320 (length,) = _struct_I.unpack(str[start:end])
00321 start = end
00322 end += length
00323 if python3:
00324 self.originator = str[start:end].decode('utf-8')
00325 else:
00326 self.originator = str[start:end]
00327 start = end
00328 end += 4
00329 (length,) = _struct_I.unpack(str[start:end])
00330 self.name = []
00331 for i in range(0, length):
00332 start = end
00333 end += 4
00334 (length,) = _struct_I.unpack(str[start:end])
00335 start = end
00336 end += length
00337 if python3:
00338 val1 = str[start:end].decode('utf-8')
00339 else:
00340 val1 = str[start:end]
00341 self.name.append(val1)
00342 start = end
00343 end += 4
00344 (length,) = _struct_I.unpack(str[start:end])
00345 self.setpoint = []
00346 for i in range(0, length):
00347 start = end
00348 end += 4
00349 (length,) = _struct_I.unpack(str[start:end])
00350 start = end
00351 end += length
00352 if python3:
00353 val1 = str[start:end].decode('utf-8')
00354 else:
00355 val1 = str[start:end]
00356 self.setpoint.append(val1)
00357 start = end
00358 end += 4
00359 (length,) = _struct_I.unpack(str[start:end])
00360 self.command = []
00361 for i in range(0, length):
00362 start = end
00363 end += 4
00364 (length,) = _struct_I.unpack(str[start:end])
00365 start = end
00366 end += length
00367 if python3:
00368 val1 = str[start:end].decode('utf-8')
00369 else:
00370 val1 = str[start:end]
00371 self.command.append(val1)
00372 start = end
00373 end += 4
00374 (length,) = _struct_I.unpack(str[start:end])
00375 pattern = '<%sd'%length
00376 start = end
00377 end += struct.calcsize(pattern)
00378 self.force = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00379 start = end
00380 end += 4
00381 (length,) = _struct_I.unpack(str[start:end])
00382 pattern = '<%sH'%length
00383 start = end
00384 end += struct.calcsize(pattern)
00385 self.dutyCycle = numpy.frombuffer(str[start:end], dtype=numpy.uint16, count=length)
00386 return self
00387 except struct.error as e:
00388 raise genpy.DeserializationError(e)
00389
00390 _struct_I = genpy.struct_I
00391 _struct_3I = struct.Struct("<3I")