00001 """autogenerated by genpy from hrpsys_gazebo_msgs/RobotState.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 geometry_msgs.msg
00008 import hrpsys_gazebo_msgs.msg
00009 import std_msgs.msg
00010
00011 class RobotState(genpy.Message):
00012 _md5sum = "5348f3f71adb0c293ad77b60d43ec14e"
00013 _type = "hrpsys_gazebo_msgs/RobotState"
00014 _has_header = True
00015 _full_text = """Header header
00016
00017 float64[] position
00018 float64[] velocity
00019 float64[] effort
00020
00021 float32[] kp_position
00022 float32[] ki_position
00023 float32[] kd_position
00024 float32[] kp_velocity
00025
00026 float32[] i_effort_min
00027 float32[] i_effort_max
00028
00029 NamedImu[] Imus
00030
00031 NamedWrench[] sensors
00032
00033 ================================================================================
00034 MSG: std_msgs/Header
00035 # Standard metadata for higher-level stamped data types.
00036 # This is generally used to communicate timestamped data
00037 # in a particular coordinate frame.
00038 #
00039 # sequence ID: consecutively increasing ID
00040 uint32 seq
00041 #Two-integer timestamp that is expressed as:
00042 # * stamp.secs: seconds (stamp_secs) since epoch
00043 # * stamp.nsecs: nanoseconds since stamp_secs
00044 # time-handling sugar is provided by the client library
00045 time stamp
00046 #Frame this data is associated with
00047 # 0: no frame
00048 # 1: global frame
00049 string frame_id
00050
00051 ================================================================================
00052 MSG: hrpsys_gazebo_msgs/NamedImu
00053 string name
00054 geometry_msgs/Quaternion orientation
00055 geometry_msgs/Vector3 angular_velocity
00056 geometry_msgs/Vector3 linear_acceleration
00057
00058 ================================================================================
00059 MSG: geometry_msgs/Quaternion
00060 # This represents an orientation in free space in quaternion form.
00061
00062 float64 x
00063 float64 y
00064 float64 z
00065 float64 w
00066
00067 ================================================================================
00068 MSG: geometry_msgs/Vector3
00069 # This represents a vector in free space.
00070
00071 float64 x
00072 float64 y
00073 float64 z
00074 ================================================================================
00075 MSG: hrpsys_gazebo_msgs/NamedWrench
00076 string Name
00077 geometry_msgs/Vector3 force
00078 geometry_msgs/Vector3 torque
00079
00080 """
00081 __slots__ = ['header','position','velocity','effort','kp_position','ki_position','kd_position','kp_velocity','i_effort_min','i_effort_max','Imus','sensors']
00082 _slot_types = ['std_msgs/Header','float64[]','float64[]','float64[]','float32[]','float32[]','float32[]','float32[]','float32[]','float32[]','hrpsys_gazebo_msgs/NamedImu[]','hrpsys_gazebo_msgs/NamedWrench[]']
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,position,velocity,effort,kp_position,ki_position,kd_position,kp_velocity,i_effort_min,i_effort_max,Imus,sensors
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(RobotState, self).__init__(*args, **kwds)
00100
00101 if self.header is None:
00102 self.header = std_msgs.msg.Header()
00103 if self.position is None:
00104 self.position = []
00105 if self.velocity is None:
00106 self.velocity = []
00107 if self.effort is None:
00108 self.effort = []
00109 if self.kp_position is None:
00110 self.kp_position = []
00111 if self.ki_position is None:
00112 self.ki_position = []
00113 if self.kd_position is None:
00114 self.kd_position = []
00115 if self.kp_velocity is None:
00116 self.kp_velocity = []
00117 if self.i_effort_min is None:
00118 self.i_effort_min = []
00119 if self.i_effort_max is None:
00120 self.i_effort_max = []
00121 if self.Imus is None:
00122 self.Imus = []
00123 if self.sensors is None:
00124 self.sensors = []
00125 else:
00126 self.header = std_msgs.msg.Header()
00127 self.position = []
00128 self.velocity = []
00129 self.effort = []
00130 self.kp_position = []
00131 self.ki_position = []
00132 self.kd_position = []
00133 self.kp_velocity = []
00134 self.i_effort_min = []
00135 self.i_effort_max = []
00136 self.Imus = []
00137 self.sensors = []
00138
00139 def _get_types(self):
00140 """
00141 internal API method
00142 """
00143 return self._slot_types
00144
00145 def serialize(self, buff):
00146 """
00147 serialize message into buffer
00148 :param buff: buffer, ``StringIO``
00149 """
00150 try:
00151 _x = self
00152 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00153 _x = self.header.frame_id
00154 length = len(_x)
00155 if python3 or type(_x) == unicode:
00156 _x = _x.encode('utf-8')
00157 length = len(_x)
00158 buff.write(struct.pack('<I%ss'%length, length, _x))
00159 length = len(self.position)
00160 buff.write(_struct_I.pack(length))
00161 pattern = '<%sd'%length
00162 buff.write(struct.pack(pattern, *self.position))
00163 length = len(self.velocity)
00164 buff.write(_struct_I.pack(length))
00165 pattern = '<%sd'%length
00166 buff.write(struct.pack(pattern, *self.velocity))
00167 length = len(self.effort)
00168 buff.write(_struct_I.pack(length))
00169 pattern = '<%sd'%length
00170 buff.write(struct.pack(pattern, *self.effort))
00171 length = len(self.kp_position)
00172 buff.write(_struct_I.pack(length))
00173 pattern = '<%sf'%length
00174 buff.write(struct.pack(pattern, *self.kp_position))
00175 length = len(self.ki_position)
00176 buff.write(_struct_I.pack(length))
00177 pattern = '<%sf'%length
00178 buff.write(struct.pack(pattern, *self.ki_position))
00179 length = len(self.kd_position)
00180 buff.write(_struct_I.pack(length))
00181 pattern = '<%sf'%length
00182 buff.write(struct.pack(pattern, *self.kd_position))
00183 length = len(self.kp_velocity)
00184 buff.write(_struct_I.pack(length))
00185 pattern = '<%sf'%length
00186 buff.write(struct.pack(pattern, *self.kp_velocity))
00187 length = len(self.i_effort_min)
00188 buff.write(_struct_I.pack(length))
00189 pattern = '<%sf'%length
00190 buff.write(struct.pack(pattern, *self.i_effort_min))
00191 length = len(self.i_effort_max)
00192 buff.write(_struct_I.pack(length))
00193 pattern = '<%sf'%length
00194 buff.write(struct.pack(pattern, *self.i_effort_max))
00195 length = len(self.Imus)
00196 buff.write(_struct_I.pack(length))
00197 for val1 in self.Imus:
00198 _x = val1.name
00199 length = len(_x)
00200 if python3 or type(_x) == unicode:
00201 _x = _x.encode('utf-8')
00202 length = len(_x)
00203 buff.write(struct.pack('<I%ss'%length, length, _x))
00204 _v1 = val1.orientation
00205 _x = _v1
00206 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00207 _v2 = val1.angular_velocity
00208 _x = _v2
00209 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00210 _v3 = val1.linear_acceleration
00211 _x = _v3
00212 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00213 length = len(self.sensors)
00214 buff.write(_struct_I.pack(length))
00215 for val1 in self.sensors:
00216 _x = val1.Name
00217 length = len(_x)
00218 if python3 or type(_x) == unicode:
00219 _x = _x.encode('utf-8')
00220 length = len(_x)
00221 buff.write(struct.pack('<I%ss'%length, length, _x))
00222 _v4 = val1.force
00223 _x = _v4
00224 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00225 _v5 = val1.torque
00226 _x = _v5
00227 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00228 except struct.error as se: self._check_types(se)
00229 except TypeError as te: self._check_types(te)
00230
00231 def deserialize(self, str):
00232 """
00233 unpack serialized message in str into this message instance
00234 :param str: byte array of serialized message, ``str``
00235 """
00236 try:
00237 if self.header is None:
00238 self.header = std_msgs.msg.Header()
00239 if self.Imus is None:
00240 self.Imus = None
00241 if self.sensors is None:
00242 self.sensors = None
00243 end = 0
00244 _x = self
00245 start = end
00246 end += 12
00247 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(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.header.frame_id = str[start:end].decode('utf-8')
00255 else:
00256 self.header.frame_id = str[start:end]
00257 start = end
00258 end += 4
00259 (length,) = _struct_I.unpack(str[start:end])
00260 pattern = '<%sd'%length
00261 start = end
00262 end += struct.calcsize(pattern)
00263 self.position = struct.unpack(pattern, str[start:end])
00264 start = end
00265 end += 4
00266 (length,) = _struct_I.unpack(str[start:end])
00267 pattern = '<%sd'%length
00268 start = end
00269 end += struct.calcsize(pattern)
00270 self.velocity = struct.unpack(pattern, str[start:end])
00271 start = end
00272 end += 4
00273 (length,) = _struct_I.unpack(str[start:end])
00274 pattern = '<%sd'%length
00275 start = end
00276 end += struct.calcsize(pattern)
00277 self.effort = struct.unpack(pattern, str[start:end])
00278 start = end
00279 end += 4
00280 (length,) = _struct_I.unpack(str[start:end])
00281 pattern = '<%sf'%length
00282 start = end
00283 end += struct.calcsize(pattern)
00284 self.kp_position = struct.unpack(pattern, str[start:end])
00285 start = end
00286 end += 4
00287 (length,) = _struct_I.unpack(str[start:end])
00288 pattern = '<%sf'%length
00289 start = end
00290 end += struct.calcsize(pattern)
00291 self.ki_position = struct.unpack(pattern, str[start:end])
00292 start = end
00293 end += 4
00294 (length,) = _struct_I.unpack(str[start:end])
00295 pattern = '<%sf'%length
00296 start = end
00297 end += struct.calcsize(pattern)
00298 self.kd_position = struct.unpack(pattern, str[start:end])
00299 start = end
00300 end += 4
00301 (length,) = _struct_I.unpack(str[start:end])
00302 pattern = '<%sf'%length
00303 start = end
00304 end += struct.calcsize(pattern)
00305 self.kp_velocity = struct.unpack(pattern, str[start:end])
00306 start = end
00307 end += 4
00308 (length,) = _struct_I.unpack(str[start:end])
00309 pattern = '<%sf'%length
00310 start = end
00311 end += struct.calcsize(pattern)
00312 self.i_effort_min = struct.unpack(pattern, str[start:end])
00313 start = end
00314 end += 4
00315 (length,) = _struct_I.unpack(str[start:end])
00316 pattern = '<%sf'%length
00317 start = end
00318 end += struct.calcsize(pattern)
00319 self.i_effort_max = struct.unpack(pattern, str[start:end])
00320 start = end
00321 end += 4
00322 (length,) = _struct_I.unpack(str[start:end])
00323 self.Imus = []
00324 for i in range(0, length):
00325 val1 = hrpsys_gazebo_msgs.msg.NamedImu()
00326 start = end
00327 end += 4
00328 (length,) = _struct_I.unpack(str[start:end])
00329 start = end
00330 end += length
00331 if python3:
00332 val1.name = str[start:end].decode('utf-8')
00333 else:
00334 val1.name = str[start:end]
00335 _v6 = val1.orientation
00336 _x = _v6
00337 start = end
00338 end += 32
00339 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00340 _v7 = val1.angular_velocity
00341 _x = _v7
00342 start = end
00343 end += 24
00344 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00345 _v8 = val1.linear_acceleration
00346 _x = _v8
00347 start = end
00348 end += 24
00349 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00350 self.Imus.append(val1)
00351 start = end
00352 end += 4
00353 (length,) = _struct_I.unpack(str[start:end])
00354 self.sensors = []
00355 for i in range(0, length):
00356 val1 = hrpsys_gazebo_msgs.msg.NamedWrench()
00357 start = end
00358 end += 4
00359 (length,) = _struct_I.unpack(str[start:end])
00360 start = end
00361 end += length
00362 if python3:
00363 val1.Name = str[start:end].decode('utf-8')
00364 else:
00365 val1.Name = str[start:end]
00366 _v9 = val1.force
00367 _x = _v9
00368 start = end
00369 end += 24
00370 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00371 _v10 = val1.torque
00372 _x = _v10
00373 start = end
00374 end += 24
00375 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00376 self.sensors.append(val1)
00377 return self
00378 except struct.error as e:
00379 raise genpy.DeserializationError(e)
00380
00381
00382 def serialize_numpy(self, buff, numpy):
00383 """
00384 serialize message with numpy array types into buffer
00385 :param buff: buffer, ``StringIO``
00386 :param numpy: numpy python module
00387 """
00388 try:
00389 _x = self
00390 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00391 _x = self.header.frame_id
00392 length = len(_x)
00393 if python3 or type(_x) == unicode:
00394 _x = _x.encode('utf-8')
00395 length = len(_x)
00396 buff.write(struct.pack('<I%ss'%length, length, _x))
00397 length = len(self.position)
00398 buff.write(_struct_I.pack(length))
00399 pattern = '<%sd'%length
00400 buff.write(self.position.tostring())
00401 length = len(self.velocity)
00402 buff.write(_struct_I.pack(length))
00403 pattern = '<%sd'%length
00404 buff.write(self.velocity.tostring())
00405 length = len(self.effort)
00406 buff.write(_struct_I.pack(length))
00407 pattern = '<%sd'%length
00408 buff.write(self.effort.tostring())
00409 length = len(self.kp_position)
00410 buff.write(_struct_I.pack(length))
00411 pattern = '<%sf'%length
00412 buff.write(self.kp_position.tostring())
00413 length = len(self.ki_position)
00414 buff.write(_struct_I.pack(length))
00415 pattern = '<%sf'%length
00416 buff.write(self.ki_position.tostring())
00417 length = len(self.kd_position)
00418 buff.write(_struct_I.pack(length))
00419 pattern = '<%sf'%length
00420 buff.write(self.kd_position.tostring())
00421 length = len(self.kp_velocity)
00422 buff.write(_struct_I.pack(length))
00423 pattern = '<%sf'%length
00424 buff.write(self.kp_velocity.tostring())
00425 length = len(self.i_effort_min)
00426 buff.write(_struct_I.pack(length))
00427 pattern = '<%sf'%length
00428 buff.write(self.i_effort_min.tostring())
00429 length = len(self.i_effort_max)
00430 buff.write(_struct_I.pack(length))
00431 pattern = '<%sf'%length
00432 buff.write(self.i_effort_max.tostring())
00433 length = len(self.Imus)
00434 buff.write(_struct_I.pack(length))
00435 for val1 in self.Imus:
00436 _x = val1.name
00437 length = len(_x)
00438 if python3 or type(_x) == unicode:
00439 _x = _x.encode('utf-8')
00440 length = len(_x)
00441 buff.write(struct.pack('<I%ss'%length, length, _x))
00442 _v11 = val1.orientation
00443 _x = _v11
00444 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00445 _v12 = val1.angular_velocity
00446 _x = _v12
00447 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00448 _v13 = val1.linear_acceleration
00449 _x = _v13
00450 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00451 length = len(self.sensors)
00452 buff.write(_struct_I.pack(length))
00453 for val1 in self.sensors:
00454 _x = val1.Name
00455 length = len(_x)
00456 if python3 or type(_x) == unicode:
00457 _x = _x.encode('utf-8')
00458 length = len(_x)
00459 buff.write(struct.pack('<I%ss'%length, length, _x))
00460 _v14 = val1.force
00461 _x = _v14
00462 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00463 _v15 = val1.torque
00464 _x = _v15
00465 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00466 except struct.error as se: self._check_types(se)
00467 except TypeError as te: self._check_types(te)
00468
00469 def deserialize_numpy(self, str, numpy):
00470 """
00471 unpack serialized message in str into this message instance using numpy for array types
00472 :param str: byte array of serialized message, ``str``
00473 :param numpy: numpy python module
00474 """
00475 try:
00476 if self.header is None:
00477 self.header = std_msgs.msg.Header()
00478 if self.Imus is None:
00479 self.Imus = None
00480 if self.sensors is None:
00481 self.sensors = None
00482 end = 0
00483 _x = self
00484 start = end
00485 end += 12
00486 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00487 start = end
00488 end += 4
00489 (length,) = _struct_I.unpack(str[start:end])
00490 start = end
00491 end += length
00492 if python3:
00493 self.header.frame_id = str[start:end].decode('utf-8')
00494 else:
00495 self.header.frame_id = str[start:end]
00496 start = end
00497 end += 4
00498 (length,) = _struct_I.unpack(str[start:end])
00499 pattern = '<%sd'%length
00500 start = end
00501 end += struct.calcsize(pattern)
00502 self.position = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00503 start = end
00504 end += 4
00505 (length,) = _struct_I.unpack(str[start:end])
00506 pattern = '<%sd'%length
00507 start = end
00508 end += struct.calcsize(pattern)
00509 self.velocity = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00510 start = end
00511 end += 4
00512 (length,) = _struct_I.unpack(str[start:end])
00513 pattern = '<%sd'%length
00514 start = end
00515 end += struct.calcsize(pattern)
00516 self.effort = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length)
00517 start = end
00518 end += 4
00519 (length,) = _struct_I.unpack(str[start:end])
00520 pattern = '<%sf'%length
00521 start = end
00522 end += struct.calcsize(pattern)
00523 self.kp_position = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00524 start = end
00525 end += 4
00526 (length,) = _struct_I.unpack(str[start:end])
00527 pattern = '<%sf'%length
00528 start = end
00529 end += struct.calcsize(pattern)
00530 self.ki_position = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00531 start = end
00532 end += 4
00533 (length,) = _struct_I.unpack(str[start:end])
00534 pattern = '<%sf'%length
00535 start = end
00536 end += struct.calcsize(pattern)
00537 self.kd_position = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00538 start = end
00539 end += 4
00540 (length,) = _struct_I.unpack(str[start:end])
00541 pattern = '<%sf'%length
00542 start = end
00543 end += struct.calcsize(pattern)
00544 self.kp_velocity = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00545 start = end
00546 end += 4
00547 (length,) = _struct_I.unpack(str[start:end])
00548 pattern = '<%sf'%length
00549 start = end
00550 end += struct.calcsize(pattern)
00551 self.i_effort_min = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00552 start = end
00553 end += 4
00554 (length,) = _struct_I.unpack(str[start:end])
00555 pattern = '<%sf'%length
00556 start = end
00557 end += struct.calcsize(pattern)
00558 self.i_effort_max = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00559 start = end
00560 end += 4
00561 (length,) = _struct_I.unpack(str[start:end])
00562 self.Imus = []
00563 for i in range(0, length):
00564 val1 = hrpsys_gazebo_msgs.msg.NamedImu()
00565 start = end
00566 end += 4
00567 (length,) = _struct_I.unpack(str[start:end])
00568 start = end
00569 end += length
00570 if python3:
00571 val1.name = str[start:end].decode('utf-8')
00572 else:
00573 val1.name = str[start:end]
00574 _v16 = val1.orientation
00575 _x = _v16
00576 start = end
00577 end += 32
00578 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00579 _v17 = val1.angular_velocity
00580 _x = _v17
00581 start = end
00582 end += 24
00583 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00584 _v18 = val1.linear_acceleration
00585 _x = _v18
00586 start = end
00587 end += 24
00588 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00589 self.Imus.append(val1)
00590 start = end
00591 end += 4
00592 (length,) = _struct_I.unpack(str[start:end])
00593 self.sensors = []
00594 for i in range(0, length):
00595 val1 = hrpsys_gazebo_msgs.msg.NamedWrench()
00596 start = end
00597 end += 4
00598 (length,) = _struct_I.unpack(str[start:end])
00599 start = end
00600 end += length
00601 if python3:
00602 val1.Name = str[start:end].decode('utf-8')
00603 else:
00604 val1.Name = str[start:end]
00605 _v19 = val1.force
00606 _x = _v19
00607 start = end
00608 end += 24
00609 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00610 _v20 = val1.torque
00611 _x = _v20
00612 start = end
00613 end += 24
00614 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00615 self.sensors.append(val1)
00616 return self
00617 except struct.error as e:
00618 raise genpy.DeserializationError(e)
00619
00620 _struct_I = genpy.struct_I
00621 _struct_3I = struct.Struct("<3I")
00622 _struct_4d = struct.Struct("<4d")
00623 _struct_3d = struct.Struct("<3d")