$search
00001 """autogenerated by genmsg_py from MotorTrace.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import ethercat_hardware.msg 00006 import std_msgs.msg 00007 00008 class MotorTrace(roslib.message.Message): 00009 _md5sum = "ada0b8b7f00967d292bd5bb4f59d4bd8" 00010 _type = "ethercat_hardware/MotorTrace" 00011 _has_header = True #flag to mark the presence of a Header object 00012 _full_text = """Header header 00013 string reason 00014 ethercat_hardware/BoardInfo board_info 00015 ethercat_hardware/ActuatorInfo actuator_info 00016 ethercat_hardware/MotorTraceSample[] samples 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: ethercat_hardware/BoardInfo 00037 string description 00038 uint32 product_code 00039 uint32 pcb 00040 uint32 pca 00041 uint32 serial 00042 uint32 firmware_major 00043 uint32 firmware_minor 00044 float64 board_resistance 00045 float64 max_pwm_ratio 00046 float64 hw_max_current 00047 bool poor_measured_motor_voltage 00048 ================================================================================ 00049 MSG: ethercat_hardware/ActuatorInfo 00050 uint32 id 00051 string name 00052 string robot_name 00053 string motor_make 00054 string motor_model 00055 float64 max_current 00056 float64 speed_constant 00057 float64 motor_resistance 00058 float64 motor_torque_constant 00059 float64 encoder_reduction 00060 float64 pulses_per_revolution 00061 ================================================================================ 00062 MSG: ethercat_hardware/MotorTraceSample 00063 float64 timestamp 00064 bool enabled 00065 float64 supply_voltage 00066 float64 measured_motor_voltage 00067 float64 programmed_pwm 00068 float64 executed_current 00069 float64 measured_current 00070 float64 velocity 00071 float64 encoder_position 00072 uint32 encoder_error_count 00073 float64 motor_voltage_error_limit 00074 float64 filtered_motor_voltage_error 00075 float64 filtered_abs_motor_voltage_error 00076 float64 filtered_measured_voltage_error 00077 float64 filtered_abs_measured_voltage_error 00078 float64 filtered_current_error 00079 float64 filtered_abs_current_error 00080 """ 00081 __slots__ = ['header','reason','board_info','actuator_info','samples'] 00082 _slot_types = ['Header','string','ethercat_hardware/BoardInfo','ethercat_hardware/ActuatorInfo','ethercat_hardware/MotorTraceSample[]'] 00083 00084 def __init__(self, *args, **kwds): 00085 """ 00086 Constructor. Any message fields that are implicitly/explicitly 00087 set to None will be assigned a default value. The recommend 00088 use is keyword arguments as this is more robust to future message 00089 changes. You cannot mix in-order arguments and keyword arguments. 00090 00091 The available fields are: 00092 header,reason,board_info,actuator_info,samples 00093 00094 @param args: complete set of field values, in .msg order 00095 @param kwds: use keyword arguments corresponding to message field names 00096 to set specific fields. 00097 """ 00098 if args or kwds: 00099 super(MotorTrace, self).__init__(*args, **kwds) 00100 #message fields cannot be None, assign default values for those that are 00101 if self.header is None: 00102 self.header = std_msgs.msg._Header.Header() 00103 if self.reason is None: 00104 self.reason = '' 00105 if self.board_info is None: 00106 self.board_info = ethercat_hardware.msg.BoardInfo() 00107 if self.actuator_info is None: 00108 self.actuator_info = ethercat_hardware.msg.ActuatorInfo() 00109 if self.samples is None: 00110 self.samples = [] 00111 else: 00112 self.header = std_msgs.msg._Header.Header() 00113 self.reason = '' 00114 self.board_info = ethercat_hardware.msg.BoardInfo() 00115 self.actuator_info = ethercat_hardware.msg.ActuatorInfo() 00116 self.samples = [] 00117 00118 def _get_types(self): 00119 """ 00120 internal API method 00121 """ 00122 return self._slot_types 00123 00124 def serialize(self, buff): 00125 """ 00126 serialize message into buffer 00127 @param buff: buffer 00128 @type buff: StringIO 00129 """ 00130 try: 00131 _x = self 00132 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00133 _x = self.header.frame_id 00134 length = len(_x) 00135 buff.write(struct.pack('<I%ss'%length, length, _x)) 00136 _x = self.reason 00137 length = len(_x) 00138 buff.write(struct.pack('<I%ss'%length, length, _x)) 00139 _x = self.board_info.description 00140 length = len(_x) 00141 buff.write(struct.pack('<I%ss'%length, length, _x)) 00142 _x = self 00143 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)) 00144 _x = self.actuator_info.name 00145 length = len(_x) 00146 buff.write(struct.pack('<I%ss'%length, length, _x)) 00147 _x = self.actuator_info.robot_name 00148 length = len(_x) 00149 buff.write(struct.pack('<I%ss'%length, length, _x)) 00150 _x = self.actuator_info.motor_make 00151 length = len(_x) 00152 buff.write(struct.pack('<I%ss'%length, length, _x)) 00153 _x = self.actuator_info.motor_model 00154 length = len(_x) 00155 buff.write(struct.pack('<I%ss'%length, length, _x)) 00156 _x = self 00157 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)) 00158 length = len(self.samples) 00159 buff.write(_struct_I.pack(length)) 00160 for val1 in self.samples: 00161 _x = val1 00162 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)) 00163 except struct.error as se: self._check_types(se) 00164 except TypeError as te: self._check_types(te) 00165 00166 def deserialize(self, str): 00167 """ 00168 unpack serialized message in str into this message instance 00169 @param str: byte array of serialized message 00170 @type str: str 00171 """ 00172 try: 00173 if self.header is None: 00174 self.header = std_msgs.msg._Header.Header() 00175 if self.board_info is None: 00176 self.board_info = ethercat_hardware.msg.BoardInfo() 00177 if self.actuator_info is None: 00178 self.actuator_info = ethercat_hardware.msg.ActuatorInfo() 00179 end = 0 00180 _x = self 00181 start = end 00182 end += 12 00183 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00184 start = end 00185 end += 4 00186 (length,) = _struct_I.unpack(str[start:end]) 00187 start = end 00188 end += length 00189 self.header.frame_id = str[start:end] 00190 start = end 00191 end += 4 00192 (length,) = _struct_I.unpack(str[start:end]) 00193 start = end 00194 end += length 00195 self.reason = str[start:end] 00196 start = end 00197 end += 4 00198 (length,) = _struct_I.unpack(str[start:end]) 00199 start = end 00200 end += length 00201 self.board_info.description = str[start:end] 00202 _x = self 00203 start = end 00204 end += 53 00205 (_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]) 00206 self.board_info.poor_measured_motor_voltage = bool(self.board_info.poor_measured_motor_voltage) 00207 start = end 00208 end += 4 00209 (length,) = _struct_I.unpack(str[start:end]) 00210 start = end 00211 end += length 00212 self.actuator_info.name = str[start:end] 00213 start = end 00214 end += 4 00215 (length,) = _struct_I.unpack(str[start:end]) 00216 start = end 00217 end += length 00218 self.actuator_info.robot_name = str[start:end] 00219 start = end 00220 end += 4 00221 (length,) = _struct_I.unpack(str[start:end]) 00222 start = end 00223 end += length 00224 self.actuator_info.motor_make = str[start:end] 00225 start = end 00226 end += 4 00227 (length,) = _struct_I.unpack(str[start:end]) 00228 start = end 00229 end += length 00230 self.actuator_info.motor_model = str[start:end] 00231 _x = self 00232 start = end 00233 end += 48 00234 (_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]) 00235 start = end 00236 end += 4 00237 (length,) = _struct_I.unpack(str[start:end]) 00238 self.samples = [] 00239 for i in range(0, length): 00240 val1 = ethercat_hardware.msg.MotorTraceSample() 00241 _x = val1 00242 start = end 00243 end += 125 00244 (_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]) 00245 val1.enabled = bool(val1.enabled) 00246 self.samples.append(val1) 00247 return self 00248 except struct.error as e: 00249 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00250 00251 00252 def serialize_numpy(self, buff, numpy): 00253 """ 00254 serialize message with numpy array types into buffer 00255 @param buff: buffer 00256 @type buff: StringIO 00257 @param numpy: numpy python module 00258 @type numpy module 00259 """ 00260 try: 00261 _x = self 00262 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00263 _x = self.header.frame_id 00264 length = len(_x) 00265 buff.write(struct.pack('<I%ss'%length, length, _x)) 00266 _x = self.reason 00267 length = len(_x) 00268 buff.write(struct.pack('<I%ss'%length, length, _x)) 00269 _x = self.board_info.description 00270 length = len(_x) 00271 buff.write(struct.pack('<I%ss'%length, length, _x)) 00272 _x = self 00273 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)) 00274 _x = self.actuator_info.name 00275 length = len(_x) 00276 buff.write(struct.pack('<I%ss'%length, length, _x)) 00277 _x = self.actuator_info.robot_name 00278 length = len(_x) 00279 buff.write(struct.pack('<I%ss'%length, length, _x)) 00280 _x = self.actuator_info.motor_make 00281 length = len(_x) 00282 buff.write(struct.pack('<I%ss'%length, length, _x)) 00283 _x = self.actuator_info.motor_model 00284 length = len(_x) 00285 buff.write(struct.pack('<I%ss'%length, length, _x)) 00286 _x = self 00287 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)) 00288 length = len(self.samples) 00289 buff.write(_struct_I.pack(length)) 00290 for val1 in self.samples: 00291 _x = val1 00292 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)) 00293 except struct.error as se: self._check_types(se) 00294 except TypeError as te: self._check_types(te) 00295 00296 def deserialize_numpy(self, str, numpy): 00297 """ 00298 unpack serialized message in str into this message instance using numpy for array types 00299 @param str: byte array of serialized message 00300 @type str: str 00301 @param numpy: numpy python module 00302 @type numpy: module 00303 """ 00304 try: 00305 if self.header is None: 00306 self.header = std_msgs.msg._Header.Header() 00307 if self.board_info is None: 00308 self.board_info = ethercat_hardware.msg.BoardInfo() 00309 if self.actuator_info is None: 00310 self.actuator_info = ethercat_hardware.msg.ActuatorInfo() 00311 end = 0 00312 _x = self 00313 start = end 00314 end += 12 00315 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00316 start = end 00317 end += 4 00318 (length,) = _struct_I.unpack(str[start:end]) 00319 start = end 00320 end += length 00321 self.header.frame_id = str[start:end] 00322 start = end 00323 end += 4 00324 (length,) = _struct_I.unpack(str[start:end]) 00325 start = end 00326 end += length 00327 self.reason = str[start:end] 00328 start = end 00329 end += 4 00330 (length,) = _struct_I.unpack(str[start:end]) 00331 start = end 00332 end += length 00333 self.board_info.description = str[start:end] 00334 _x = self 00335 start = end 00336 end += 53 00337 (_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]) 00338 self.board_info.poor_measured_motor_voltage = bool(self.board_info.poor_measured_motor_voltage) 00339 start = end 00340 end += 4 00341 (length,) = _struct_I.unpack(str[start:end]) 00342 start = end 00343 end += length 00344 self.actuator_info.name = str[start:end] 00345 start = end 00346 end += 4 00347 (length,) = _struct_I.unpack(str[start:end]) 00348 start = end 00349 end += length 00350 self.actuator_info.robot_name = str[start:end] 00351 start = end 00352 end += 4 00353 (length,) = _struct_I.unpack(str[start:end]) 00354 start = end 00355 end += length 00356 self.actuator_info.motor_make = str[start:end] 00357 start = end 00358 end += 4 00359 (length,) = _struct_I.unpack(str[start:end]) 00360 start = end 00361 end += length 00362 self.actuator_info.motor_model = str[start:end] 00363 _x = self 00364 start = end 00365 end += 48 00366 (_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]) 00367 start = end 00368 end += 4 00369 (length,) = _struct_I.unpack(str[start:end]) 00370 self.samples = [] 00371 for i in range(0, length): 00372 val1 = ethercat_hardware.msg.MotorTraceSample() 00373 _x = val1 00374 start = end 00375 end += 125 00376 (_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]) 00377 val1.enabled = bool(val1.enabled) 00378 self.samples.append(val1) 00379 return self 00380 except struct.error as e: 00381 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00382 00383 _struct_I = roslib.message.struct_I 00384 _struct_3I = struct.Struct("<3I") 00385 _struct_6I3dBI = struct.Struct("<6I3dBI") 00386 _struct_6d = struct.Struct("<6d") 00387 _struct_dB7dI7d = struct.Struct("<dB7dI7d")