00001 """autogenerated by genmsg_py from MechanismStatistics.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import pr2_mechanism_msgs.msg
00006 import roslib.rostime
00007 import std_msgs.msg
00008
00009 class MechanismStatistics(roslib.message.Message):
00010 _md5sum = "b4a99069393681672c01f8c823458e04"
00011 _type = "pr2_mechanism_msgs/MechanismStatistics"
00012 _has_header = True
00013 _full_text = """# This message describes the state of the pr2 mechanism. It contains the state of
00014 # each actuator, each joint, and each controller that is spawned in pr2_mechanism_control.
00015
00016 Header header
00017 ActuatorStatistics[] actuator_statistics
00018 JointStatistics[] joint_statistics
00019 ControllerStatistics[] controller_statistics
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 MSG: pr2_mechanism_msgs/ActuatorStatistics
00041 # This message contains the state of an actuator on the pr2 robot.
00042 # An actuator contains a motor and an encoder, and is connected
00043 # to a joint by a transmission
00044
00045 # the name of the actuator
00046 string name
00047
00048 # the sequence number of the MCB in the ethercat chain.
00049 # the first device in the chain gets deviced_id zero
00050 int32 device_id
00051
00052 # the time at which this actuator state was measured
00053 time timestamp
00054
00055 # the encoder position, represented by the number of encoder ticks
00056 int32 encoder_count
00057
00058 # The angular offset (in radians) that is added to the encoder reading,
00059 # to get to the position of the actuator. This number is computed when the referece
00060 # sensor is triggered during the calibration phase
00061 float64 encoder_offset
00062
00063 # the encoder position in radians
00064 float64 position
00065
00066 # the encoder velocity in encoder ticks per second
00067 float64 encoder_velocity
00068
00069 # the encoder velocity in radians per second
00070 float64 velocity
00071
00072 # the value of the calibration reading: low (false) or high (true)
00073 bool calibration_reading
00074
00075 # bool to indicate if the joint already triggered the rising/falling edge of the reference sensor
00076 bool calibration_rising_edge_valid
00077 bool calibration_falling_edge_valid
00078
00079 # the encoder position when the last rising/falling edge was observed.
00080 # only read this value when the calibration_rising/falling_edge_valid is true
00081 float64 last_calibration_rising_edge
00082 float64 last_calibration_falling_edge
00083
00084 # flag to indicate if this actuator is enabled or not.
00085 # An actuator can only be commanded when it is enabled.
00086 bool is_enabled
00087
00088 # indicates if the motor is halted. A motor can be halted because of a voltage or communication problem
00089 bool halted
00090
00091 # the last current/effort command that was requested
00092 float64 last_commanded_current
00093 float64 last_commanded_effort
00094
00095 # the last current/effort command that was executed by the actuator
00096 float64 last_executed_current
00097 float64 last_executed_effort
00098
00099 # the last current/effort that was measured by the actuator
00100 float64 last_measured_current
00101 float64 last_measured_effort
00102
00103 # the motor voltate
00104 float64 motor_voltage
00105
00106 # the number of detected encoder problems
00107 int32 num_encoder_errors
00108
00109
00110 ================================================================================
00111 MSG: pr2_mechanism_msgs/JointStatistics
00112 # This message contains the state of one joint of the pr2 robot.
00113 # This message is specificly designed for the pr2 robot.
00114 # A generic joint state message can be found in sensor_msgs::JointState
00115
00116 # the name of the joint
00117 string name
00118
00119 # the time at which these joint statistics were measured
00120 time timestamp
00121
00122 # the position of the joint in radians
00123 float64 position
00124
00125 # the velocity of the joint in radians per second
00126 float64 velocity
00127
00128 # the measured joint effort
00129 float64 measured_effort
00130
00131 # the effort that was commanded to the joint.
00132 # the actual applied effort might be different
00133 # because the safety code can limit the effort
00134 # a joint can apply
00135 float64 commanded_effort
00136
00137 # a flag indicating if the joint is calibrated or not
00138 bool is_calibrated
00139
00140 # a flag inidcating if the joint violated one of its position/velocity/effort limits
00141 # in the last publish cycle
00142 bool violated_limits
00143
00144 # the total distance travelled by the joint, measured in radians.
00145 float64 odometer
00146
00147 # the lowest position reached by the joint in the last publish cycle
00148 float64 min_position
00149
00150 # the highest position reached by the joint in the last publish cycle
00151 float64 max_position
00152
00153 # the maximum absolute velocity reached by the joint in the last publish cycle
00154 float64 max_abs_velocity
00155
00156 # the maximum absolute effort applied by the joint in the last publish cycle
00157 float64 max_abs_effort
00158
00159 ================================================================================
00160 MSG: pr2_mechanism_msgs/ControllerStatistics
00161 # This message contains the state of one realtime controller
00162 # that was spawned in pr2_mechanism_control
00163
00164 # the name of the controller
00165 string name
00166
00167 # the time at which these controller statistics were measured
00168 time timestamp
00169
00170 # bool that indicates if the controller is currently
00171 # in a running or a stopped state
00172 bool running
00173
00174 # the maximum time the update loop of the controller ever needed to complete
00175 duration max_time
00176
00177 # the average time the update loop of the controller needs to complete.
00178 # the average is computed in a sliding time window.
00179 duration mean_time
00180
00181 # the variance on the time the update loop of the controller needs to complete.
00182 # the variance applies to a sliding time window.
00183 duration variance_time
00184
00185 # the number of times this controller broke the realtime loop
00186 int32 num_control_loop_overruns
00187
00188 # the timestamp of the last time this controller broke the realtime loop
00189 time time_last_control_loop_overrun
00190 """
00191 __slots__ = ['header','actuator_statistics','joint_statistics','controller_statistics']
00192 _slot_types = ['Header','pr2_mechanism_msgs/ActuatorStatistics[]','pr2_mechanism_msgs/JointStatistics[]','pr2_mechanism_msgs/ControllerStatistics[]']
00193
00194 def __init__(self, *args, **kwds):
00195 """
00196 Constructor. Any message fields that are implicitly/explicitly
00197 set to None will be assigned a default value. The recommend
00198 use is keyword arguments as this is more robust to future message
00199 changes. You cannot mix in-order arguments and keyword arguments.
00200
00201 The available fields are:
00202 header,actuator_statistics,joint_statistics,controller_statistics
00203
00204 @param args: complete set of field values, in .msg order
00205 @param kwds: use keyword arguments corresponding to message field names
00206 to set specific fields.
00207 """
00208 if args or kwds:
00209 super(MechanismStatistics, self).__init__(*args, **kwds)
00210
00211 if self.header is None:
00212 self.header = std_msgs.msg._Header.Header()
00213 if self.actuator_statistics is None:
00214 self.actuator_statistics = []
00215 if self.joint_statistics is None:
00216 self.joint_statistics = []
00217 if self.controller_statistics is None:
00218 self.controller_statistics = []
00219 else:
00220 self.header = std_msgs.msg._Header.Header()
00221 self.actuator_statistics = []
00222 self.joint_statistics = []
00223 self.controller_statistics = []
00224
00225 def _get_types(self):
00226 """
00227 internal API method
00228 """
00229 return self._slot_types
00230
00231 def serialize(self, buff):
00232 """
00233 serialize message into buffer
00234 @param buff: buffer
00235 @type buff: StringIO
00236 """
00237 try:
00238 _x = self
00239 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00240 _x = self.header.frame_id
00241 length = len(_x)
00242 buff.write(struct.pack('<I%ss'%length, length, _x))
00243 length = len(self.actuator_statistics)
00244 buff.write(_struct_I.pack(length))
00245 for val1 in self.actuator_statistics:
00246 _x = val1.name
00247 length = len(_x)
00248 buff.write(struct.pack('<I%ss'%length, length, _x))
00249 buff.write(_struct_i.pack(val1.device_id))
00250 _v1 = val1.timestamp
00251 _x = _v1
00252 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00253 _x = val1
00254 buff.write(_struct_i4d3B2d2B7di.pack(_x.encoder_count, _x.encoder_offset, _x.position, _x.encoder_velocity, _x.velocity, _x.calibration_reading, _x.calibration_rising_edge_valid, _x.calibration_falling_edge_valid, _x.last_calibration_rising_edge, _x.last_calibration_falling_edge, _x.is_enabled, _x.halted, _x.last_commanded_current, _x.last_commanded_effort, _x.last_executed_current, _x.last_executed_effort, _x.last_measured_current, _x.last_measured_effort, _x.motor_voltage, _x.num_encoder_errors))
00255 length = len(self.joint_statistics)
00256 buff.write(_struct_I.pack(length))
00257 for val1 in self.joint_statistics:
00258 _x = val1.name
00259 length = len(_x)
00260 buff.write(struct.pack('<I%ss'%length, length, _x))
00261 _v2 = val1.timestamp
00262 _x = _v2
00263 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00264 _x = val1
00265 buff.write(_struct_4d2B5d.pack(_x.position, _x.velocity, _x.measured_effort, _x.commanded_effort, _x.is_calibrated, _x.violated_limits, _x.odometer, _x.min_position, _x.max_position, _x.max_abs_velocity, _x.max_abs_effort))
00266 length = len(self.controller_statistics)
00267 buff.write(_struct_I.pack(length))
00268 for val1 in self.controller_statistics:
00269 _x = val1.name
00270 length = len(_x)
00271 buff.write(struct.pack('<I%ss'%length, length, _x))
00272 _v3 = val1.timestamp
00273 _x = _v3
00274 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00275 buff.write(_struct_B.pack(val1.running))
00276 _v4 = val1.max_time
00277 _x = _v4
00278 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00279 _v5 = val1.mean_time
00280 _x = _v5
00281 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00282 _v6 = val1.variance_time
00283 _x = _v6
00284 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00285 buff.write(_struct_i.pack(val1.num_control_loop_overruns))
00286 _v7 = val1.time_last_control_loop_overrun
00287 _x = _v7
00288 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00289 except struct.error, se: self._check_types(se)
00290 except TypeError, te: self._check_types(te)
00291
00292 def deserialize(self, str):
00293 """
00294 unpack serialized message in str into this message instance
00295 @param str: byte array of serialized message
00296 @type str: str
00297 """
00298 try:
00299 if self.header is None:
00300 self.header = std_msgs.msg._Header.Header()
00301 end = 0
00302 _x = self
00303 start = end
00304 end += 12
00305 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00306 start = end
00307 end += 4
00308 (length,) = _struct_I.unpack(str[start:end])
00309 start = end
00310 end += length
00311 self.header.frame_id = str[start:end]
00312 start = end
00313 end += 4
00314 (length,) = _struct_I.unpack(str[start:end])
00315 self.actuator_statistics = []
00316 for i in xrange(0, length):
00317 val1 = pr2_mechanism_msgs.msg.ActuatorStatistics()
00318 start = end
00319 end += 4
00320 (length,) = _struct_I.unpack(str[start:end])
00321 start = end
00322 end += length
00323 val1.name = str[start:end]
00324 start = end
00325 end += 4
00326 (val1.device_id,) = _struct_i.unpack(str[start:end])
00327 _v8 = val1.timestamp
00328 _x = _v8
00329 start = end
00330 end += 8
00331 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00332 _x = val1
00333 start = end
00334 end += 117
00335 (_x.encoder_count, _x.encoder_offset, _x.position, _x.encoder_velocity, _x.velocity, _x.calibration_reading, _x.calibration_rising_edge_valid, _x.calibration_falling_edge_valid, _x.last_calibration_rising_edge, _x.last_calibration_falling_edge, _x.is_enabled, _x.halted, _x.last_commanded_current, _x.last_commanded_effort, _x.last_executed_current, _x.last_executed_effort, _x.last_measured_current, _x.last_measured_effort, _x.motor_voltage, _x.num_encoder_errors,) = _struct_i4d3B2d2B7di.unpack(str[start:end])
00336 val1.calibration_reading = bool(val1.calibration_reading)
00337 val1.calibration_rising_edge_valid = bool(val1.calibration_rising_edge_valid)
00338 val1.calibration_falling_edge_valid = bool(val1.calibration_falling_edge_valid)
00339 val1.is_enabled = bool(val1.is_enabled)
00340 val1.halted = bool(val1.halted)
00341 self.actuator_statistics.append(val1)
00342 start = end
00343 end += 4
00344 (length,) = _struct_I.unpack(str[start:end])
00345 self.joint_statistics = []
00346 for i in xrange(0, length):
00347 val1 = pr2_mechanism_msgs.msg.JointStatistics()
00348 start = end
00349 end += 4
00350 (length,) = _struct_I.unpack(str[start:end])
00351 start = end
00352 end += length
00353 val1.name = str[start:end]
00354 _v9 = val1.timestamp
00355 _x = _v9
00356 start = end
00357 end += 8
00358 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00359 _x = val1
00360 start = end
00361 end += 74
00362 (_x.position, _x.velocity, _x.measured_effort, _x.commanded_effort, _x.is_calibrated, _x.violated_limits, _x.odometer, _x.min_position, _x.max_position, _x.max_abs_velocity, _x.max_abs_effort,) = _struct_4d2B5d.unpack(str[start:end])
00363 val1.is_calibrated = bool(val1.is_calibrated)
00364 val1.violated_limits = bool(val1.violated_limits)
00365 self.joint_statistics.append(val1)
00366 start = end
00367 end += 4
00368 (length,) = _struct_I.unpack(str[start:end])
00369 self.controller_statistics = []
00370 for i in xrange(0, length):
00371 val1 = pr2_mechanism_msgs.msg.ControllerStatistics()
00372 start = end
00373 end += 4
00374 (length,) = _struct_I.unpack(str[start:end])
00375 start = end
00376 end += length
00377 val1.name = str[start:end]
00378 _v10 = val1.timestamp
00379 _x = _v10
00380 start = end
00381 end += 8
00382 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00383 start = end
00384 end += 1
00385 (val1.running,) = _struct_B.unpack(str[start:end])
00386 val1.running = bool(val1.running)
00387 _v11 = val1.max_time
00388 _x = _v11
00389 start = end
00390 end += 8
00391 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00392 _v12 = val1.mean_time
00393 _x = _v12
00394 start = end
00395 end += 8
00396 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00397 _v13 = val1.variance_time
00398 _x = _v13
00399 start = end
00400 end += 8
00401 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00402 start = end
00403 end += 4
00404 (val1.num_control_loop_overruns,) = _struct_i.unpack(str[start:end])
00405 _v14 = val1.time_last_control_loop_overrun
00406 _x = _v14
00407 start = end
00408 end += 8
00409 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00410 self.controller_statistics.append(val1)
00411 return self
00412 except struct.error, e:
00413 raise roslib.message.DeserializationError(e)
00414
00415
00416 def serialize_numpy(self, buff, numpy):
00417 """
00418 serialize message with numpy array types into buffer
00419 @param buff: buffer
00420 @type buff: StringIO
00421 @param numpy: numpy python module
00422 @type numpy module
00423 """
00424 try:
00425 _x = self
00426 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00427 _x = self.header.frame_id
00428 length = len(_x)
00429 buff.write(struct.pack('<I%ss'%length, length, _x))
00430 length = len(self.actuator_statistics)
00431 buff.write(_struct_I.pack(length))
00432 for val1 in self.actuator_statistics:
00433 _x = val1.name
00434 length = len(_x)
00435 buff.write(struct.pack('<I%ss'%length, length, _x))
00436 buff.write(_struct_i.pack(val1.device_id))
00437 _v15 = val1.timestamp
00438 _x = _v15
00439 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00440 _x = val1
00441 buff.write(_struct_i4d3B2d2B7di.pack(_x.encoder_count, _x.encoder_offset, _x.position, _x.encoder_velocity, _x.velocity, _x.calibration_reading, _x.calibration_rising_edge_valid, _x.calibration_falling_edge_valid, _x.last_calibration_rising_edge, _x.last_calibration_falling_edge, _x.is_enabled, _x.halted, _x.last_commanded_current, _x.last_commanded_effort, _x.last_executed_current, _x.last_executed_effort, _x.last_measured_current, _x.last_measured_effort, _x.motor_voltage, _x.num_encoder_errors))
00442 length = len(self.joint_statistics)
00443 buff.write(_struct_I.pack(length))
00444 for val1 in self.joint_statistics:
00445 _x = val1.name
00446 length = len(_x)
00447 buff.write(struct.pack('<I%ss'%length, length, _x))
00448 _v16 = val1.timestamp
00449 _x = _v16
00450 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00451 _x = val1
00452 buff.write(_struct_4d2B5d.pack(_x.position, _x.velocity, _x.measured_effort, _x.commanded_effort, _x.is_calibrated, _x.violated_limits, _x.odometer, _x.min_position, _x.max_position, _x.max_abs_velocity, _x.max_abs_effort))
00453 length = len(self.controller_statistics)
00454 buff.write(_struct_I.pack(length))
00455 for val1 in self.controller_statistics:
00456 _x = val1.name
00457 length = len(_x)
00458 buff.write(struct.pack('<I%ss'%length, length, _x))
00459 _v17 = val1.timestamp
00460 _x = _v17
00461 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00462 buff.write(_struct_B.pack(val1.running))
00463 _v18 = val1.max_time
00464 _x = _v18
00465 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00466 _v19 = val1.mean_time
00467 _x = _v19
00468 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00469 _v20 = val1.variance_time
00470 _x = _v20
00471 buff.write(_struct_2i.pack(_x.secs, _x.nsecs))
00472 buff.write(_struct_i.pack(val1.num_control_loop_overruns))
00473 _v21 = val1.time_last_control_loop_overrun
00474 _x = _v21
00475 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00476 except struct.error, se: self._check_types(se)
00477 except TypeError, te: self._check_types(te)
00478
00479 def deserialize_numpy(self, str, numpy):
00480 """
00481 unpack serialized message in str into this message instance using numpy for array types
00482 @param str: byte array of serialized message
00483 @type str: str
00484 @param numpy: numpy python module
00485 @type numpy: module
00486 """
00487 try:
00488 if self.header is None:
00489 self.header = std_msgs.msg._Header.Header()
00490 end = 0
00491 _x = self
00492 start = end
00493 end += 12
00494 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00495 start = end
00496 end += 4
00497 (length,) = _struct_I.unpack(str[start:end])
00498 start = end
00499 end += length
00500 self.header.frame_id = str[start:end]
00501 start = end
00502 end += 4
00503 (length,) = _struct_I.unpack(str[start:end])
00504 self.actuator_statistics = []
00505 for i in xrange(0, length):
00506 val1 = pr2_mechanism_msgs.msg.ActuatorStatistics()
00507 start = end
00508 end += 4
00509 (length,) = _struct_I.unpack(str[start:end])
00510 start = end
00511 end += length
00512 val1.name = str[start:end]
00513 start = end
00514 end += 4
00515 (val1.device_id,) = _struct_i.unpack(str[start:end])
00516 _v22 = val1.timestamp
00517 _x = _v22
00518 start = end
00519 end += 8
00520 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00521 _x = val1
00522 start = end
00523 end += 117
00524 (_x.encoder_count, _x.encoder_offset, _x.position, _x.encoder_velocity, _x.velocity, _x.calibration_reading, _x.calibration_rising_edge_valid, _x.calibration_falling_edge_valid, _x.last_calibration_rising_edge, _x.last_calibration_falling_edge, _x.is_enabled, _x.halted, _x.last_commanded_current, _x.last_commanded_effort, _x.last_executed_current, _x.last_executed_effort, _x.last_measured_current, _x.last_measured_effort, _x.motor_voltage, _x.num_encoder_errors,) = _struct_i4d3B2d2B7di.unpack(str[start:end])
00525 val1.calibration_reading = bool(val1.calibration_reading)
00526 val1.calibration_rising_edge_valid = bool(val1.calibration_rising_edge_valid)
00527 val1.calibration_falling_edge_valid = bool(val1.calibration_falling_edge_valid)
00528 val1.is_enabled = bool(val1.is_enabled)
00529 val1.halted = bool(val1.halted)
00530 self.actuator_statistics.append(val1)
00531 start = end
00532 end += 4
00533 (length,) = _struct_I.unpack(str[start:end])
00534 self.joint_statistics = []
00535 for i in xrange(0, length):
00536 val1 = pr2_mechanism_msgs.msg.JointStatistics()
00537 start = end
00538 end += 4
00539 (length,) = _struct_I.unpack(str[start:end])
00540 start = end
00541 end += length
00542 val1.name = str[start:end]
00543 _v23 = val1.timestamp
00544 _x = _v23
00545 start = end
00546 end += 8
00547 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00548 _x = val1
00549 start = end
00550 end += 74
00551 (_x.position, _x.velocity, _x.measured_effort, _x.commanded_effort, _x.is_calibrated, _x.violated_limits, _x.odometer, _x.min_position, _x.max_position, _x.max_abs_velocity, _x.max_abs_effort,) = _struct_4d2B5d.unpack(str[start:end])
00552 val1.is_calibrated = bool(val1.is_calibrated)
00553 val1.violated_limits = bool(val1.violated_limits)
00554 self.joint_statistics.append(val1)
00555 start = end
00556 end += 4
00557 (length,) = _struct_I.unpack(str[start:end])
00558 self.controller_statistics = []
00559 for i in xrange(0, length):
00560 val1 = pr2_mechanism_msgs.msg.ControllerStatistics()
00561 start = end
00562 end += 4
00563 (length,) = _struct_I.unpack(str[start:end])
00564 start = end
00565 end += length
00566 val1.name = str[start:end]
00567 _v24 = val1.timestamp
00568 _x = _v24
00569 start = end
00570 end += 8
00571 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00572 start = end
00573 end += 1
00574 (val1.running,) = _struct_B.unpack(str[start:end])
00575 val1.running = bool(val1.running)
00576 _v25 = val1.max_time
00577 _x = _v25
00578 start = end
00579 end += 8
00580 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00581 _v26 = val1.mean_time
00582 _x = _v26
00583 start = end
00584 end += 8
00585 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00586 _v27 = val1.variance_time
00587 _x = _v27
00588 start = end
00589 end += 8
00590 (_x.secs, _x.nsecs,) = _struct_2i.unpack(str[start:end])
00591 start = end
00592 end += 4
00593 (val1.num_control_loop_overruns,) = _struct_i.unpack(str[start:end])
00594 _v28 = val1.time_last_control_loop_overrun
00595 _x = _v28
00596 start = end
00597 end += 8
00598 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00599 self.controller_statistics.append(val1)
00600 return self
00601 except struct.error, e:
00602 raise roslib.message.DeserializationError(e)
00603
00604 _struct_I = roslib.message.struct_I
00605 _struct_B = struct.Struct("<B")
00606 _struct_i = struct.Struct("<i")
00607 _struct_2i = struct.Struct("<2i")
00608 _struct_4d2B5d = struct.Struct("<4d2B5d")
00609 _struct_3I = struct.Struct("<3I")
00610 _struct_i4d3B2d2B7di = struct.Struct("<i4d3B2d2B7di")
00611 _struct_2I = struct.Struct("<2I")