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