00001 """autogenerated by genpy from calibration_msgs/ChainMeasurement.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 sensor_msgs.msg
00008 import std_msgs.msg
00009
00010 class ChainMeasurement(genpy.Message):
00011 _md5sum = "a57d957972fc9bc34b14f2a3cac0fbae"
00012 _type = "calibration_msgs/ChainMeasurement"
00013 _has_header = True
00014 _full_text = """Header header
00015 string chain_id
00016 sensor_msgs/JointState chain_state
00017
00018 ================================================================================
00019 MSG: std_msgs/Header
00020 # Standard metadata for higher-level stamped data types.
00021 # This is generally used to communicate timestamped data
00022 # in a particular coordinate frame.
00023 #
00024 # sequence ID: consecutively increasing ID
00025 uint32 seq
00026 #Two-integer timestamp that is expressed as:
00027 # * stamp.secs: seconds (stamp_secs) since epoch
00028 # * stamp.nsecs: nanoseconds since stamp_secs
00029 # time-handling sugar is provided by the client library
00030 time stamp
00031 #Frame this data is associated with
00032 # 0: no frame
00033 # 1: global frame
00034 string frame_id
00035
00036 ================================================================================
00037 MSG: sensor_msgs/JointState
00038 # This is a message that holds data to describe the state of a set of torque controlled joints.
00039 #
00040 # The state of each joint (revolute or prismatic) is defined by:
00041 # * the position of the joint (rad or m),
00042 # * the velocity of the joint (rad/s or m/s) and
00043 # * the effort that is applied in the joint (Nm or N).
00044 #
00045 # Each joint is uniquely identified by its name
00046 # The header specifies the time at which the joint states were recorded. All the joint states
00047 # in one message have to be recorded at the same time.
00048 #
00049 # This message consists of a multiple arrays, one for each part of the joint state.
00050 # The goal is to make each of the fields optional. When e.g. your joints have no
00051 # effort associated with them, you can leave the effort array empty.
00052 #
00053 # All arrays in this message should have the same size, or be empty.
00054 # This is the only way to uniquely associate the joint name with the correct
00055 # states.
00056
00057
00058 Header header
00059
00060 string[] name
00061 float64[] position
00062 float64[] velocity
00063 float64[] effort
00064
00065 """
00066 __slots__ = ['header','chain_id','chain_state']
00067 _slot_types = ['std_msgs/Header','string','sensor_msgs/JointState']
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 header,chain_id,chain_state
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(ChainMeasurement, self).__init__(*args, **kwds)
00085
00086 if self.header is None:
00087 self.header = std_msgs.msg.Header()
00088 if self.chain_id is None:
00089 self.chain_id = ''
00090 if self.chain_state is None:
00091 self.chain_state = sensor_msgs.msg.JointState()
00092 else:
00093 self.header = std_msgs.msg.Header()
00094 self.chain_id = ''
00095 self.chain_state = sensor_msgs.msg.JointState()
00096
00097 def _get_types(self):
00098 """
00099 internal API method
00100 """
00101 return self._slot_types
00102
00103 def serialize(self, buff):
00104 """
00105 serialize message into buffer
00106 :param buff: buffer, ``StringIO``
00107 """
00108 try:
00109 _x = self
00110 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00111 _x = self.header.frame_id
00112 length = len(_x)
00113 if python3 or type(_x) == unicode:
00114 _x = _x.encode('utf-8')
00115 length = len(_x)
00116 buff.write(struct.pack('<I%ss'%length, length, _x))
00117 _x = self.chain_id
00118 length = len(_x)
00119 if python3 or type(_x) == unicode:
00120 _x = _x.encode('utf-8')
00121 length = len(_x)
00122 buff.write(struct.pack('<I%ss'%length, length, _x))
00123 _x = self
00124 buff.write(_struct_3I.pack(_x.chain_state.header.seq, _x.chain_state.header.stamp.secs, _x.chain_state.header.stamp.nsecs))
00125 _x = self.chain_state.header.frame_id
00126 length = len(_x)
00127 if python3 or type(_x) == unicode:
00128 _x = _x.encode('utf-8')
00129 length = len(_x)
00130 buff.write(struct.pack('<I%ss'%length, length, _x))
00131 length = len(self.chain_state.name)
00132 buff.write(_struct_I.pack(length))
00133 for val1 in self.chain_state.name:
00134 length = len(val1)
00135 if python3 or type(val1) == unicode:
00136 val1 = val1.encode('utf-8')
00137 length = len(val1)
00138 buff.write(struct.pack('<I%ss'%length, length, val1))
00139 length = len(self.chain_state.position)
00140 buff.write(_struct_I.pack(length))
00141 pattern = '<%sd'%length
00142 buff.write(struct.pack(pattern, *self.chain_state.position))
00143 length = len(self.chain_state.velocity)
00144 buff.write(_struct_I.pack(length))
00145 pattern = '<%sd'%length
00146 buff.write(struct.pack(pattern, *self.chain_state.velocity))
00147 length = len(self.chain_state.effort)
00148 buff.write(_struct_I.pack(length))
00149 pattern = '<%sd'%length
00150 buff.write(struct.pack(pattern, *self.chain_state.effort))
00151 except struct.error as se: self._check_types(se)
00152 except TypeError as te: self._check_types(te)
00153
00154 def deserialize(self, str):
00155 """
00156 unpack serialized message in str into this message instance
00157 :param str: byte array of serialized message, ``str``
00158 """
00159 try:
00160 if self.header is None:
00161 self.header = std_msgs.msg.Header()
00162 if self.chain_state is None:
00163 self.chain_state = sensor_msgs.msg.JointState()
00164 end = 0
00165 _x = self
00166 start = end
00167 end += 12
00168 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00169 start = end
00170 end += 4
00171 (length,) = _struct_I.unpack(str[start:end])
00172 start = end
00173 end += length
00174 if python3:
00175 self.header.frame_id = str[start:end].decode('utf-8')
00176 else:
00177 self.header.frame_id = str[start:end]
00178 start = end
00179 end += 4
00180 (length,) = _struct_I.unpack(str[start:end])
00181 start = end
00182 end += length
00183 if python3:
00184 self.chain_id = str[start:end].decode('utf-8')
00185 else:
00186 self.chain_id = str[start:end]
00187 _x = self
00188 start = end
00189 end += 12
00190 (_x.chain_state.header.seq, _x.chain_state.header.stamp.secs, _x.chain_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00191 start = end
00192 end += 4
00193 (length,) = _struct_I.unpack(str[start:end])
00194 start = end
00195 end += length
00196 if python3:
00197 self.chain_state.header.frame_id = str[start:end].decode('utf-8')
00198 else:
00199 self.chain_state.header.frame_id = str[start:end]
00200 start = end
00201 end += 4
00202 (length,) = _struct_I.unpack(str[start:end])
00203 self.chain_state.name = []
00204 for i in range(0, length):
00205 start = end
00206 end += 4
00207 (length,) = _struct_I.unpack(str[start:end])
00208 start = end
00209 end += length
00210 if python3:
00211 val1 = str[start:end].decode('utf-8')
00212 else:
00213 val1 = str[start:end]
00214 self.chain_state.name.append(val1)
00215 start = end
00216 end += 4
00217 (length,) = _struct_I.unpack(str[start:end])
00218 pattern = '<%sd'%length
00219 start = end
00220 end += struct.calcsize(pattern)
00221 self.chain_state.position = struct.unpack(pattern, str[start:end])
00222 start = end
00223 end += 4
00224 (length,) = _struct_I.unpack(str[start:end])
00225 pattern = '<%sd'%length
00226 start = end
00227 end += struct.calcsize(pattern)
00228 self.chain_state.velocity = struct.unpack(pattern, str[start:end])
00229 start = end
00230 end += 4
00231 (length,) = _struct_I.unpack(str[start:end])
00232 pattern = '<%sd'%length
00233 start = end
00234 end += struct.calcsize(pattern)
00235 self.chain_state.effort = struct.unpack(pattern, str[start:end])
00236 return self
00237 except struct.error as e:
00238 raise genpy.DeserializationError(e)
00239
00240
00241 def serialize_numpy(self, buff, numpy):
00242 """
00243 serialize message with numpy array types into buffer
00244 :param buff: buffer, ``StringIO``
00245 :param numpy: numpy python module
00246 """
00247 try:
00248 _x = self
00249 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00250 _x = self.header.frame_id
00251 length = len(_x)
00252 if python3 or type(_x) == unicode:
00253 _x = _x.encode('utf-8')
00254 length = len(_x)
00255 buff.write(struct.pack('<I%ss'%length, length, _x))
00256 _x = self.chain_id
00257 length = len(_x)
00258 if python3 or type(_x) == unicode:
00259 _x = _x.encode('utf-8')
00260 length = len(_x)
00261 buff.write(struct.pack('<I%ss'%length, length, _x))
00262 _x = self
00263 buff.write(_struct_3I.pack(_x.chain_state.header.seq, _x.chain_state.header.stamp.secs, _x.chain_state.header.stamp.nsecs))
00264 _x = self.chain_state.header.frame_id
00265 length = len(_x)
00266 if python3 or type(_x) == unicode:
00267 _x = _x.encode('utf-8')
00268 length = len(_x)
00269 buff.write(struct.pack('<I%ss'%length, length, _x))
00270 length = len(self.chain_state.name)
00271 buff.write(_struct_I.pack(length))
00272 for val1 in self.chain_state.name:
00273 length = len(val1)
00274 if python3 or type(val1) == unicode:
00275 val1 = val1.encode('utf-8')
00276 length = len(val1)
00277 buff.write(struct.pack('<I%ss'%length, length, val1))
00278 length = len(self.chain_state.position)
00279 buff.write(_struct_I.pack(length))
00280 pattern = '<%sd'%length
00281 buff.write(self.chain_state.position.tostring())
00282 length = len(self.chain_state.velocity)
00283 buff.write(_struct_I.pack(length))
00284 pattern = '<%sd'%length
00285 buff.write(self.chain_state.velocity.tostring())
00286 length = len(self.chain_state.effort)
00287 buff.write(_struct_I.pack(length))
00288 pattern = '<%sd'%length
00289 buff.write(self.chain_state.effort.tostring())
00290 except struct.error as se: self._check_types(se)
00291 except TypeError as te: self._check_types(te)
00292
00293 def deserialize_numpy(self, str, numpy):
00294 """
00295 unpack serialized message in str into this message instance using numpy for array types
00296 :param str: byte array of serialized message, ``str``
00297 :param numpy: numpy python module
00298 """
00299 try:
00300 if self.header is None:
00301 self.header = std_msgs.msg.Header()
00302 if self.chain_state is None:
00303 self.chain_state = sensor_msgs.msg.JointState()
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.chain_id = str[start:end].decode('utf-8')
00325 else:
00326 self.chain_id = str[start:end]
00327 _x = self
00328 start = end
00329 end += 12
00330 (_x.chain_state.header.seq, _x.chain_state.header.stamp.secs, _x.chain_state.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00331 start = end
00332 end += 4
00333 (length,) = _struct_I.unpack(str[start:end])
00334 start = end
00335 end += length
00336 if python3:
00337 self.chain_state.header.frame_id = str[start:end].decode('utf-8')
00338 else:
00339 self.chain_state.header.frame_id = str[start:end]
00340 start = end
00341 end += 4
00342 (length,) = _struct_I.unpack(str[start:end])
00343 self.chain_state.name = []
00344 for i in range(0, length):
00345 start = end
00346 end += 4
00347 (length,) = _struct_I.unpack(str[start:end])
00348 start = end
00349 end += length
00350 if python3:
00351 val1 = str[start:end].decode('utf-8')
00352 else:
00353 val1 = str[start:end]
00354 self.chain_state.name.append(val1)
00355 start = end
00356 end += 4
00357 (length,) = _struct_I.unpack(str[start:end])
00358 pattern = '<%sd'%length
00359 start = end
00360 end += struct.calcsize(pattern)
00361 self.chain_state.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00362 start = end
00363 end += 4
00364 (length,) = _struct_I.unpack(str[start:end])
00365 pattern = '<%sd'%length
00366 start = end
00367 end += struct.calcsize(pattern)
00368 self.chain_state.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00369 start = end
00370 end += 4
00371 (length,) = _struct_I.unpack(str[start:end])
00372 pattern = '<%sd'%length
00373 start = end
00374 end += struct.calcsize(pattern)
00375 self.chain_state.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00376 return self
00377 except struct.error as e:
00378 raise genpy.DeserializationError(e)
00379
00380 _struct_I = genpy.struct_I
00381 _struct_3I = struct.Struct("<3I")