00001 """autogenerated by genpy from ethercat_hardware/MotorTrace.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 ethercat_hardware.msg
00008 import std_msgs.msg
00009
00010 class MotorTrace(genpy.Message):
00011 _md5sum = "ada0b8b7f00967d292bd5bb4f59d4bd8"
00012 _type = "ethercat_hardware/MotorTrace"
00013 _has_header = True
00014 _full_text = """Header header
00015 string reason
00016 ethercat_hardware/BoardInfo board_info
00017 ethercat_hardware/ActuatorInfo actuator_info
00018 ethercat_hardware/MotorTraceSample[] samples
00019 ================================================================================
00020 MSG: std_msgs/Header
00021 # Standard metadata for higher-level stamped data types.
00022 # This is generally used to communicate timestamped data
00023 # in a particular coordinate frame.
00024 #
00025 # sequence ID: consecutively increasing ID
00026 uint32 seq
00027 #Two-integer timestamp that is expressed as:
00028 # * stamp.secs: seconds (stamp_secs) since epoch
00029 # * stamp.nsecs: nanoseconds since stamp_secs
00030 # time-handling sugar is provided by the client library
00031 time stamp
00032 #Frame this data is associated with
00033 # 0: no frame
00034 # 1: global frame
00035 string frame_id
00036
00037 ================================================================================
00038 MSG: ethercat_hardware/BoardInfo
00039 string description
00040 uint32 product_code
00041 uint32 pcb
00042 uint32 pca
00043 uint32 serial
00044 uint32 firmware_major
00045 uint32 firmware_minor
00046 float64 board_resistance
00047 float64 max_pwm_ratio
00048 float64 hw_max_current
00049 bool poor_measured_motor_voltage
00050 ================================================================================
00051 MSG: ethercat_hardware/ActuatorInfo
00052 uint32 id
00053 string name
00054 string robot_name
00055 string motor_make
00056 string motor_model
00057 float64 max_current
00058 float64 speed_constant
00059 float64 motor_resistance
00060 float64 motor_torque_constant
00061 float64 encoder_reduction
00062 float64 pulses_per_revolution
00063 ================================================================================
00064 MSG: ethercat_hardware/MotorTraceSample
00065 float64 timestamp
00066 bool enabled
00067 float64 supply_voltage
00068 float64 measured_motor_voltage
00069 float64 programmed_pwm
00070 float64 executed_current
00071 float64 measured_current
00072 float64 velocity
00073 float64 encoder_position
00074 uint32 encoder_error_count
00075 float64 motor_voltage_error_limit
00076 float64 filtered_motor_voltage_error
00077 float64 filtered_abs_motor_voltage_error
00078 float64 filtered_measured_voltage_error
00079 float64 filtered_abs_measured_voltage_error
00080 float64 filtered_current_error
00081 float64 filtered_abs_current_error
00082 """
00083 __slots__ = ['header','reason','board_info','actuator_info','samples']
00084 _slot_types = ['std_msgs/Header','string','ethercat_hardware/BoardInfo','ethercat_hardware/ActuatorInfo','ethercat_hardware/MotorTraceSample[]']
00085
00086 def __init__(self, *args, **kwds):
00087 """
00088 Constructor. Any message fields that are implicitly/explicitly
00089 set to None will be assigned a default value. The recommend
00090 use is keyword arguments as this is more robust to future message
00091 changes. You cannot mix in-order arguments and keyword arguments.
00092
00093 The available fields are:
00094 header,reason,board_info,actuator_info,samples
00095
00096 :param args: complete set of field values, in .msg order
00097 :param kwds: use keyword arguments corresponding to message field names
00098 to set specific fields.
00099 """
00100 if args or kwds:
00101 super(MotorTrace, self).__init__(*args, **kwds)
00102
00103 if self.header is None:
00104 self.header = std_msgs.msg.Header()
00105 if self.reason is None:
00106 self.reason = ''
00107 if self.board_info is None:
00108 self.board_info = ethercat_hardware.msg.BoardInfo()
00109 if self.actuator_info is None:
00110 self.actuator_info = ethercat_hardware.msg.ActuatorInfo()
00111 if self.samples is None:
00112 self.samples = []
00113 else:
00114 self.header = std_msgs.msg.Header()
00115 self.reason = ''
00116 self.board_info = ethercat_hardware.msg.BoardInfo()
00117 self.actuator_info = ethercat_hardware.msg.ActuatorInfo()
00118 self.samples = []
00119
00120 def _get_types(self):
00121 """
00122 internal API method
00123 """
00124 return self._slot_types
00125
00126 def serialize(self, buff):
00127 """
00128 serialize message into buffer
00129 :param buff: buffer, ``StringIO``
00130 """
00131 try:
00132 _x = self
00133 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00134 _x = self.header.frame_id
00135 length = len(_x)
00136 if python3 or type(_x) == unicode:
00137 _x = _x.encode('utf-8')
00138 length = len(_x)
00139 buff.write(struct.pack('<I%ss'%length, length, _x))
00140 _x = self.reason
00141 length = len(_x)
00142 if python3 or type(_x) == unicode:
00143 _x = _x.encode('utf-8')
00144 length = len(_x)
00145 buff.write(struct.pack('<I%ss'%length, length, _x))
00146 _x = self.board_info.description
00147 length = len(_x)
00148 if python3 or type(_x) == unicode:
00149 _x = _x.encode('utf-8')
00150 length = len(_x)
00151 buff.write(struct.pack('<I%ss'%length, length, _x))
00152 _x = self
00153 buff.write(_struct_6I3dBI.pack(_x.board_info.product_code, _x.board_info.pcb, _x.board_info.pca, _x.board_info.serial, _x.board_info.firmware_major, _x.board_info.firmware_minor, _x.board_info.board_resistance, _x.board_info.max_pwm_ratio, _x.board_info.hw_max_current, _x.board_info.poor_measured_motor_voltage, _x.actuator_info.id))
00154 _x = self.actuator_info.name
00155 length = len(_x)
00156 if python3 or type(_x) == unicode:
00157 _x = _x.encode('utf-8')
00158 length = len(_x)
00159 buff.write(struct.pack('<I%ss'%length, length, _x))
00160 _x = self.actuator_info.robot_name
00161 length = len(_x)
00162 if python3 or type(_x) == unicode:
00163 _x = _x.encode('utf-8')
00164 length = len(_x)
00165 buff.write(struct.pack('<I%ss'%length, length, _x))
00166 _x = self.actuator_info.motor_make
00167 length = len(_x)
00168 if python3 or type(_x) == unicode:
00169 _x = _x.encode('utf-8')
00170 length = len(_x)
00171 buff.write(struct.pack('<I%ss'%length, length, _x))
00172 _x = self.actuator_info.motor_model
00173 length = len(_x)
00174 if python3 or type(_x) == unicode:
00175 _x = _x.encode('utf-8')
00176 length = len(_x)
00177 buff.write(struct.pack('<I%ss'%length, length, _x))
00178 _x = self
00179 buff.write(_struct_6d.pack(_x.actuator_info.max_current, _x.actuator_info.speed_constant, _x.actuator_info.motor_resistance, _x.actuator_info.motor_torque_constant, _x.actuator_info.encoder_reduction, _x.actuator_info.pulses_per_revolution))
00180 length = len(self.samples)
00181 buff.write(_struct_I.pack(length))
00182 for val1 in self.samples:
00183 _x = val1
00184 buff.write(_struct_dB7dI7d.pack(_x.timestamp, _x.enabled, _x.supply_voltage, _x.measured_motor_voltage, _x.programmed_pwm, _x.executed_current, _x.measured_current, _x.velocity, _x.encoder_position, _x.encoder_error_count, _x.motor_voltage_error_limit, _x.filtered_motor_voltage_error, _x.filtered_abs_motor_voltage_error, _x.filtered_measured_voltage_error, _x.filtered_abs_measured_voltage_error, _x.filtered_current_error, _x.filtered_abs_current_error))
00185 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00186 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00187
00188 def deserialize(self, str):
00189 """
00190 unpack serialized message in str into this message instance
00191 :param str: byte array of serialized message, ``str``
00192 """
00193 try:
00194 if self.header is None:
00195 self.header = std_msgs.msg.Header()
00196 if self.board_info is None:
00197 self.board_info = ethercat_hardware.msg.BoardInfo()
00198 if self.actuator_info is None:
00199 self.actuator_info = ethercat_hardware.msg.ActuatorInfo()
00200 if self.samples is None:
00201 self.samples = None
00202 end = 0
00203 _x = self
00204 start = end
00205 end += 12
00206 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00207 start = end
00208 end += 4
00209 (length,) = _struct_I.unpack(str[start:end])
00210 start = end
00211 end += length
00212 if python3:
00213 self.header.frame_id = str[start:end].decode('utf-8')
00214 else:
00215 self.header.frame_id = str[start:end]
00216 start = end
00217 end += 4
00218 (length,) = _struct_I.unpack(str[start:end])
00219 start = end
00220 end += length
00221 if python3:
00222 self.reason = str[start:end].decode('utf-8')
00223 else:
00224 self.reason = str[start:end]
00225 start = end
00226 end += 4
00227 (length,) = _struct_I.unpack(str[start:end])
00228 start = end
00229 end += length
00230 if python3:
00231 self.board_info.description = str[start:end].decode('utf-8')
00232 else:
00233 self.board_info.description = str[start:end]
00234 _x = self
00235 start = end
00236 end += 53
00237 (_x.board_info.product_code, _x.board_info.pcb, _x.board_info.pca, _x.board_info.serial, _x.board_info.firmware_major, _x.board_info.firmware_minor, _x.board_info.board_resistance, _x.board_info.max_pwm_ratio, _x.board_info.hw_max_current, _x.board_info.poor_measured_motor_voltage, _x.actuator_info.id,) = _struct_6I3dBI.unpack(str[start:end])
00238 self.board_info.poor_measured_motor_voltage = bool(self.board_info.poor_measured_motor_voltage)
00239 start = end
00240 end += 4
00241 (length,) = _struct_I.unpack(str[start:end])
00242 start = end
00243 end += length
00244 if python3:
00245 self.actuator_info.name = str[start:end].decode('utf-8')
00246 else:
00247 self.actuator_info.name = str[start:end]
00248 start = end
00249 end += 4
00250 (length,) = _struct_I.unpack(str[start:end])
00251 start = end
00252 end += length
00253 if python3:
00254 self.actuator_info.robot_name = str[start:end].decode('utf-8')
00255 else:
00256 self.actuator_info.robot_name = 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 self.actuator_info.motor_make = str[start:end].decode('utf-8')
00264 else:
00265 self.actuator_info.motor_make = str[start:end]
00266 start = end
00267 end += 4
00268 (length,) = _struct_I.unpack(str[start:end])
00269 start = end
00270 end += length
00271 if python3:
00272 self.actuator_info.motor_model = str[start:end].decode('utf-8')
00273 else:
00274 self.actuator_info.motor_model = str[start:end]
00275 _x = self
00276 start = end
00277 end += 48
00278 (_x.actuator_info.max_current, _x.actuator_info.speed_constant, _x.actuator_info.motor_resistance, _x.actuator_info.motor_torque_constant, _x.actuator_info.encoder_reduction, _x.actuator_info.pulses_per_revolution,) = _struct_6d.unpack(str[start:end])
00279 start = end
00280 end += 4
00281 (length,) = _struct_I.unpack(str[start:end])
00282 self.samples = []
00283 for i in range(0, length):
00284 val1 = ethercat_hardware.msg.MotorTraceSample()
00285 _x = val1
00286 start = end
00287 end += 125
00288 (_x.timestamp, _x.enabled, _x.supply_voltage, _x.measured_motor_voltage, _x.programmed_pwm, _x.executed_current, _x.measured_current, _x.velocity, _x.encoder_position, _x.encoder_error_count, _x.motor_voltage_error_limit, _x.filtered_motor_voltage_error, _x.filtered_abs_motor_voltage_error, _x.filtered_measured_voltage_error, _x.filtered_abs_measured_voltage_error, _x.filtered_current_error, _x.filtered_abs_current_error,) = _struct_dB7dI7d.unpack(str[start:end])
00289 val1.enabled = bool(val1.enabled)
00290 self.samples.append(val1)
00291 return self
00292 except struct.error as e:
00293 raise genpy.DeserializationError(e)
00294
00295
00296 def serialize_numpy(self, buff, numpy):
00297 """
00298 serialize message with numpy array types into buffer
00299 :param buff: buffer, ``StringIO``
00300 :param numpy: numpy python module
00301 """
00302 try:
00303 _x = self
00304 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00305 _x = self.header.frame_id
00306 length = len(_x)
00307 if python3 or type(_x) == unicode:
00308 _x = _x.encode('utf-8')
00309 length = len(_x)
00310 buff.write(struct.pack('<I%ss'%length, length, _x))
00311 _x = self.reason
00312 length = len(_x)
00313 if python3 or type(_x) == unicode:
00314 _x = _x.encode('utf-8')
00315 length = len(_x)
00316 buff.write(struct.pack('<I%ss'%length, length, _x))
00317 _x = self.board_info.description
00318 length = len(_x)
00319 if python3 or type(_x) == unicode:
00320 _x = _x.encode('utf-8')
00321 length = len(_x)
00322 buff.write(struct.pack('<I%ss'%length, length, _x))
00323 _x = self
00324 buff.write(_struct_6I3dBI.pack(_x.board_info.product_code, _x.board_info.pcb, _x.board_info.pca, _x.board_info.serial, _x.board_info.firmware_major, _x.board_info.firmware_minor, _x.board_info.board_resistance, _x.board_info.max_pwm_ratio, _x.board_info.hw_max_current, _x.board_info.poor_measured_motor_voltage, _x.actuator_info.id))
00325 _x = self.actuator_info.name
00326 length = len(_x)
00327 if python3 or type(_x) == unicode:
00328 _x = _x.encode('utf-8')
00329 length = len(_x)
00330 buff.write(struct.pack('<I%ss'%length, length, _x))
00331 _x = self.actuator_info.robot_name
00332 length = len(_x)
00333 if python3 or type(_x) == unicode:
00334 _x = _x.encode('utf-8')
00335 length = len(_x)
00336 buff.write(struct.pack('<I%ss'%length, length, _x))
00337 _x = self.actuator_info.motor_make
00338 length = len(_x)
00339 if python3 or type(_x) == unicode:
00340 _x = _x.encode('utf-8')
00341 length = len(_x)
00342 buff.write(struct.pack('<I%ss'%length, length, _x))
00343 _x = self.actuator_info.motor_model
00344 length = len(_x)
00345 if python3 or type(_x) == unicode:
00346 _x = _x.encode('utf-8')
00347 length = len(_x)
00348 buff.write(struct.pack('<I%ss'%length, length, _x))
00349 _x = self
00350 buff.write(_struct_6d.pack(_x.actuator_info.max_current, _x.actuator_info.speed_constant, _x.actuator_info.motor_resistance, _x.actuator_info.motor_torque_constant, _x.actuator_info.encoder_reduction, _x.actuator_info.pulses_per_revolution))
00351 length = len(self.samples)
00352 buff.write(_struct_I.pack(length))
00353 for val1 in self.samples:
00354 _x = val1
00355 buff.write(_struct_dB7dI7d.pack(_x.timestamp, _x.enabled, _x.supply_voltage, _x.measured_motor_voltage, _x.programmed_pwm, _x.executed_current, _x.measured_current, _x.velocity, _x.encoder_position, _x.encoder_error_count, _x.motor_voltage_error_limit, _x.filtered_motor_voltage_error, _x.filtered_abs_motor_voltage_error, _x.filtered_measured_voltage_error, _x.filtered_abs_measured_voltage_error, _x.filtered_current_error, _x.filtered_abs_current_error))
00356 except struct.error as se: self._check_types(struct.error("%s: '%s' when writing '%s'" % (type(se), str(se), str(_x))))
00357 except TypeError as te: self._check_types(ValueError("%s: '%s' when writing '%s'" % (type(te), str(te), str(_x))))
00358
00359 def deserialize_numpy(self, str, numpy):
00360 """
00361 unpack serialized message in str into this message instance using numpy for array types
00362 :param str: byte array of serialized message, ``str``
00363 :param numpy: numpy python module
00364 """
00365 try:
00366 if self.header is None:
00367 self.header = std_msgs.msg.Header()
00368 if self.board_info is None:
00369 self.board_info = ethercat_hardware.msg.BoardInfo()
00370 if self.actuator_info is None:
00371 self.actuator_info = ethercat_hardware.msg.ActuatorInfo()
00372 if self.samples is None:
00373 self.samples = None
00374 end = 0
00375 _x = self
00376 start = end
00377 end += 12
00378 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00379 start = end
00380 end += 4
00381 (length,) = _struct_I.unpack(str[start:end])
00382 start = end
00383 end += length
00384 if python3:
00385 self.header.frame_id = str[start:end].decode('utf-8')
00386 else:
00387 self.header.frame_id = str[start:end]
00388 start = end
00389 end += 4
00390 (length,) = _struct_I.unpack(str[start:end])
00391 start = end
00392 end += length
00393 if python3:
00394 self.reason = str[start:end].decode('utf-8')
00395 else:
00396 self.reason = str[start:end]
00397 start = end
00398 end += 4
00399 (length,) = _struct_I.unpack(str[start:end])
00400 start = end
00401 end += length
00402 if python3:
00403 self.board_info.description = str[start:end].decode('utf-8')
00404 else:
00405 self.board_info.description = str[start:end]
00406 _x = self
00407 start = end
00408 end += 53
00409 (_x.board_info.product_code, _x.board_info.pcb, _x.board_info.pca, _x.board_info.serial, _x.board_info.firmware_major, _x.board_info.firmware_minor, _x.board_info.board_resistance, _x.board_info.max_pwm_ratio, _x.board_info.hw_max_current, _x.board_info.poor_measured_motor_voltage, _x.actuator_info.id,) = _struct_6I3dBI.unpack(str[start:end])
00410 self.board_info.poor_measured_motor_voltage = bool(self.board_info.poor_measured_motor_voltage)
00411 start = end
00412 end += 4
00413 (length,) = _struct_I.unpack(str[start:end])
00414 start = end
00415 end += length
00416 if python3:
00417 self.actuator_info.name = str[start:end].decode('utf-8')
00418 else:
00419 self.actuator_info.name = str[start:end]
00420 start = end
00421 end += 4
00422 (length,) = _struct_I.unpack(str[start:end])
00423 start = end
00424 end += length
00425 if python3:
00426 self.actuator_info.robot_name = str[start:end].decode('utf-8')
00427 else:
00428 self.actuator_info.robot_name = str[start:end]
00429 start = end
00430 end += 4
00431 (length,) = _struct_I.unpack(str[start:end])
00432 start = end
00433 end += length
00434 if python3:
00435 self.actuator_info.motor_make = str[start:end].decode('utf-8')
00436 else:
00437 self.actuator_info.motor_make = str[start:end]
00438 start = end
00439 end += 4
00440 (length,) = _struct_I.unpack(str[start:end])
00441 start = end
00442 end += length
00443 if python3:
00444 self.actuator_info.motor_model = str[start:end].decode('utf-8')
00445 else:
00446 self.actuator_info.motor_model = str[start:end]
00447 _x = self
00448 start = end
00449 end += 48
00450 (_x.actuator_info.max_current, _x.actuator_info.speed_constant, _x.actuator_info.motor_resistance, _x.actuator_info.motor_torque_constant, _x.actuator_info.encoder_reduction, _x.actuator_info.pulses_per_revolution,) = _struct_6d.unpack(str[start:end])
00451 start = end
00452 end += 4
00453 (length,) = _struct_I.unpack(str[start:end])
00454 self.samples = []
00455 for i in range(0, length):
00456 val1 = ethercat_hardware.msg.MotorTraceSample()
00457 _x = val1
00458 start = end
00459 end += 125
00460 (_x.timestamp, _x.enabled, _x.supply_voltage, _x.measured_motor_voltage, _x.programmed_pwm, _x.executed_current, _x.measured_current, _x.velocity, _x.encoder_position, _x.encoder_error_count, _x.motor_voltage_error_limit, _x.filtered_motor_voltage_error, _x.filtered_abs_motor_voltage_error, _x.filtered_measured_voltage_error, _x.filtered_abs_measured_voltage_error, _x.filtered_current_error, _x.filtered_abs_current_error,) = _struct_dB7dI7d.unpack(str[start:end])
00461 val1.enabled = bool(val1.enabled)
00462 self.samples.append(val1)
00463 return self
00464 except struct.error as e:
00465 raise genpy.DeserializationError(e)
00466
00467 _struct_I = genpy.struct_I
00468 _struct_3I = struct.Struct("<3I")
00469 _struct_6I3dBI = struct.Struct("<6I3dBI")
00470 _struct_6d = struct.Struct("<6d")
00471 _struct_dB7dI7d = struct.Struct("<dB7dI7d")