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