00001 """autogenerated by genpy from nasa_r2_common_msgs/JointStatusArray.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 nasa_r2_common_msgs.msg
00008 import std_msgs.msg
00009
00010 class JointStatusArray(genpy.Message):
00011 _md5sum = "db132c4fff9528f41c0236d435100eda"
00012 _type = "nasa_r2_common_msgs/JointStatusArray"
00013 _has_header = True
00014 _full_text = """Header header
00015 JointStatus[] status
00016
00017 ================================================================================
00018 MSG: std_msgs/Header
00019 # Standard metadata for higher-level stamped data types.
00020 # This is generally used to communicate timestamped data
00021 # in a particular coordinate frame.
00022 #
00023 # sequence ID: consecutively increasing ID
00024 uint32 seq
00025 #Two-integer timestamp that is expressed as:
00026 # * stamp.secs: seconds (stamp_secs) since epoch
00027 # * stamp.nsecs: nanoseconds since stamp_secs
00028 # time-handling sugar is provided by the client library
00029 time stamp
00030 #Frame this data is associated with
00031 # 0: no frame
00032 # 1: global frame
00033 string frame_id
00034
00035 ================================================================================
00036 MSG: nasa_r2_common_msgs/JointStatus
00037 string publisher
00038 string joint
00039 uint32 registerValue
00040 bool coeffsLoaded
00041 bool bridgeEnabled
00042 bool motorEnabled
00043 bool brakeReleased
00044 bool motorPowerDetected
00045 bool embeddedMotCom
00046 bool jointFaulted
00047
00048 """
00049 __slots__ = ['header','status']
00050 _slot_types = ['std_msgs/Header','nasa_r2_common_msgs/JointStatus[]']
00051
00052 def __init__(self, *args, **kwds):
00053 """
00054 Constructor. Any message fields that are implicitly/explicitly
00055 set to None will be assigned a default value. The recommend
00056 use is keyword arguments as this is more robust to future message
00057 changes. You cannot mix in-order arguments and keyword arguments.
00058
00059 The available fields are:
00060 header,status
00061
00062 :param args: complete set of field values, in .msg order
00063 :param kwds: use keyword arguments corresponding to message field names
00064 to set specific fields.
00065 """
00066 if args or kwds:
00067 super(JointStatusArray, self).__init__(*args, **kwds)
00068
00069 if self.header is None:
00070 self.header = std_msgs.msg.Header()
00071 if self.status is None:
00072 self.status = []
00073 else:
00074 self.header = std_msgs.msg.Header()
00075 self.status = []
00076
00077 def _get_types(self):
00078 """
00079 internal API method
00080 """
00081 return self._slot_types
00082
00083 def serialize(self, buff):
00084 """
00085 serialize message into buffer
00086 :param buff: buffer, ``StringIO``
00087 """
00088 try:
00089 _x = self
00090 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00091 _x = self.header.frame_id
00092 length = len(_x)
00093 if python3 or type(_x) == unicode:
00094 _x = _x.encode('utf-8')
00095 length = len(_x)
00096 buff.write(struct.pack('<I%ss'%length, length, _x))
00097 length = len(self.status)
00098 buff.write(_struct_I.pack(length))
00099 for val1 in self.status:
00100 _x = val1.publisher
00101 length = len(_x)
00102 if python3 or type(_x) == unicode:
00103 _x = _x.encode('utf-8')
00104 length = len(_x)
00105 buff.write(struct.pack('<I%ss'%length, length, _x))
00106 _x = val1.joint
00107 length = len(_x)
00108 if python3 or type(_x) == unicode:
00109 _x = _x.encode('utf-8')
00110 length = len(_x)
00111 buff.write(struct.pack('<I%ss'%length, length, _x))
00112 _x = val1
00113 buff.write(_struct_I7B.pack(_x.registerValue, _x.coeffsLoaded, _x.bridgeEnabled, _x.motorEnabled, _x.brakeReleased, _x.motorPowerDetected, _x.embeddedMotCom, _x.jointFaulted))
00114 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00115 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00116
00117 def deserialize(self, str):
00118 """
00119 unpack serialized message in str into this message instance
00120 :param str: byte array of serialized message, ``str``
00121 """
00122 try:
00123 if self.header is None:
00124 self.header = std_msgs.msg.Header()
00125 if self.status is None:
00126 self.status = None
00127 end = 0
00128 _x = self
00129 start = end
00130 end += 12
00131 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00132 start = end
00133 end += 4
00134 (length,) = _struct_I.unpack(str[start:end])
00135 start = end
00136 end += length
00137 if python3:
00138 self.header.frame_id = str[start:end].decode('utf-8')
00139 else:
00140 self.header.frame_id = str[start:end]
00141 start = end
00142 end += 4
00143 (length,) = _struct_I.unpack(str[start:end])
00144 self.status = []
00145 for i in range(0, length):
00146 val1 = nasa_r2_common_msgs.msg.JointStatus()
00147 start = end
00148 end += 4
00149 (length,) = _struct_I.unpack(str[start:end])
00150 start = end
00151 end += length
00152 if python3:
00153 val1.publisher = str[start:end].decode('utf-8')
00154 else:
00155 val1.publisher = str[start:end]
00156 start = end
00157 end += 4
00158 (length,) = _struct_I.unpack(str[start:end])
00159 start = end
00160 end += length
00161 if python3:
00162 val1.joint = str[start:end].decode('utf-8')
00163 else:
00164 val1.joint = str[start:end]
00165 _x = val1
00166 start = end
00167 end += 11
00168 (_x.registerValue, _x.coeffsLoaded, _x.bridgeEnabled, _x.motorEnabled, _x.brakeReleased, _x.motorPowerDetected, _x.embeddedMotCom, _x.jointFaulted,) = _struct_I7B.unpack(str[start:end])
00169 val1.coeffsLoaded = bool(val1.coeffsLoaded)
00170 val1.bridgeEnabled = bool(val1.bridgeEnabled)
00171 val1.motorEnabled = bool(val1.motorEnabled)
00172 val1.brakeReleased = bool(val1.brakeReleased)
00173 val1.motorPowerDetected = bool(val1.motorPowerDetected)
00174 val1.embeddedMotCom = bool(val1.embeddedMotCom)
00175 val1.jointFaulted = bool(val1.jointFaulted)
00176 self.status.append(val1)
00177 return self
00178 except struct.error as e:
00179 raise genpy.DeserializationError(e)
00180
00181
00182 def serialize_numpy(self, buff, numpy):
00183 """
00184 serialize message with numpy array types into buffer
00185 :param buff: buffer, ``StringIO``
00186 :param numpy: numpy python module
00187 """
00188 try:
00189 _x = self
00190 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00191 _x = self.header.frame_id
00192 length = len(_x)
00193 if python3 or type(_x) == unicode:
00194 _x = _x.encode('utf-8')
00195 length = len(_x)
00196 buff.write(struct.pack('<I%ss'%length, length, _x))
00197 length = len(self.status)
00198 buff.write(_struct_I.pack(length))
00199 for val1 in self.status:
00200 _x = val1.publisher
00201 length = len(_x)
00202 if python3 or type(_x) == unicode:
00203 _x = _x.encode('utf-8')
00204 length = len(_x)
00205 buff.write(struct.pack('<I%ss'%length, length, _x))
00206 _x = val1.joint
00207 length = len(_x)
00208 if python3 or type(_x) == unicode:
00209 _x = _x.encode('utf-8')
00210 length = len(_x)
00211 buff.write(struct.pack('<I%ss'%length, length, _x))
00212 _x = val1
00213 buff.write(_struct_I7B.pack(_x.registerValue, _x.coeffsLoaded, _x.bridgeEnabled, _x.motorEnabled, _x.brakeReleased, _x.motorPowerDetected, _x.embeddedMotCom, _x.jointFaulted))
00214 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00215 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00216
00217 def deserialize_numpy(self, str, numpy):
00218 """
00219 unpack serialized message in str into this message instance using numpy for array types
00220 :param str: byte array of serialized message, ``str``
00221 :param numpy: numpy python module
00222 """
00223 try:
00224 if self.header is None:
00225 self.header = std_msgs.msg.Header()
00226 if self.status is None:
00227 self.status = None
00228 end = 0
00229 _x = self
00230 start = end
00231 end += 12
00232 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00233 start = end
00234 end += 4
00235 (length,) = _struct_I.unpack(str[start:end])
00236 start = end
00237 end += length
00238 if python3:
00239 self.header.frame_id = str[start:end].decode('utf-8')
00240 else:
00241 self.header.frame_id = str[start:end]
00242 start = end
00243 end += 4
00244 (length,) = _struct_I.unpack(str[start:end])
00245 self.status = []
00246 for i in range(0, length):
00247 val1 = nasa_r2_common_msgs.msg.JointStatus()
00248 start = end
00249 end += 4
00250 (length,) = _struct_I.unpack(str[start:end])
00251 start = end
00252 end += length
00253 if python3:
00254 val1.publisher = str[start:end].decode('utf-8')
00255 else:
00256 val1.publisher = str[start:end]
00257 start = end
00258 end += 4
00259 (length,) = _struct_I.unpack(str[start:end])
00260 start = end
00261 end += length
00262 if python3:
00263 val1.joint = str[start:end].decode('utf-8')
00264 else:
00265 val1.joint = str[start:end]
00266 _x = val1
00267 start = end
00268 end += 11
00269 (_x.registerValue, _x.coeffsLoaded, _x.bridgeEnabled, _x.motorEnabled, _x.brakeReleased, _x.motorPowerDetected, _x.embeddedMotCom, _x.jointFaulted,) = _struct_I7B.unpack(str[start:end])
00270 val1.coeffsLoaded = bool(val1.coeffsLoaded)
00271 val1.bridgeEnabled = bool(val1.bridgeEnabled)
00272 val1.motorEnabled = bool(val1.motorEnabled)
00273 val1.brakeReleased = bool(val1.brakeReleased)
00274 val1.motorPowerDetected = bool(val1.motorPowerDetected)
00275 val1.embeddedMotCom = bool(val1.embeddedMotCom)
00276 val1.jointFaulted = bool(val1.jointFaulted)
00277 self.status.append(val1)
00278 return self
00279 except struct.error as e:
00280 raise genpy.DeserializationError(e)
00281
00282 _struct_I = genpy.struct_I
00283 _struct_3I = struct.Struct("<3I")
00284 _struct_I7B = struct.Struct("<I7B")