00001 """autogenerated by genmsg_py from ObjectSegmentationGuiActionResult.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import tabletop_object_detector.msg
00006 import roslib.rostime
00007 import actionlib_msgs.msg
00008 import geometry_msgs.msg
00009 import sensor_msgs.msg
00010 import object_segmentation_gui.msg
00011 import std_msgs.msg
00012
00013 class ObjectSegmentationGuiActionResult(roslib.message.Message):
00014 _md5sum = "cc714201d66909436687fe31c7901317"
00015 _type = "object_segmentation_gui/ObjectSegmentationGuiActionResult"
00016 _has_header = True
00017 _full_text = """# ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00018
00019 Header header
00020 actionlib_msgs/GoalStatus status
00021 ObjectSegmentationGuiResult result
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: actionlib_msgs/GoalStatus
00043 GoalID goal_id
00044 uint8 status
00045 uint8 PENDING = 0 # The goal has yet to be processed by the action server
00046 uint8 ACTIVE = 1 # The goal is currently being processed by the action server
00047 uint8 PREEMPTED = 2 # The goal received a cancel request after it started executing
00048 # and has since completed its execution (Terminal State)
00049 uint8 SUCCEEDED = 3 # The goal was achieved successfully by the action server (Terminal State)
00050 uint8 ABORTED = 4 # The goal was aborted during execution by the action server due
00051 # to some failure (Terminal State)
00052 uint8 REJECTED = 5 # The goal was rejected by the action server without being processed,
00053 # because the goal was unattainable or invalid (Terminal State)
00054 uint8 PREEMPTING = 6 # The goal received a cancel request after it started executing
00055 # and has not yet completed execution
00056 uint8 RECALLING = 7 # The goal received a cancel request before it started executing,
00057 # but the action server has not yet confirmed that the goal is canceled
00058 uint8 RECALLED = 8 # The goal received a cancel request before it started executing
00059 # and was successfully cancelled (Terminal State)
00060 uint8 LOST = 9 # An action client can determine that a goal is LOST. This should not be
00061 # sent over the wire by an action server
00062
00063 #Allow for the user to associate a string with GoalStatus for debugging
00064 string text
00065
00066
00067 ================================================================================
00068 MSG: actionlib_msgs/GoalID
00069 # The stamp should store the time at which this goal was requested.
00070 # It is used by an action server when it tries to preempt all
00071 # goals that were requested before a certain time
00072 time stamp
00073
00074 # The id provides a way to associate feedback and
00075 # result message with specific goal requests. The id
00076 # specified must be unique.
00077 string id
00078
00079
00080 ================================================================================
00081 MSG: object_segmentation_gui/ObjectSegmentationGuiResult
00082 # ====== DO NOT MODIFY! AUTOGENERATED FROM AN ACTION DEFINITION ======
00083 # The information for the plane that has been detected
00084 tabletop_object_detector/Table table
00085
00086 # The raw clusters detected in the scan
00087 sensor_msgs/PointCloud[] clusters
00088
00089 # Whether the detection has succeeded or failed
00090 int32 NO_CLOUD_RECEIVED = 1
00091 int32 NO_TABLE = 2
00092 int32 OTHER_ERROR = 3
00093 int32 SUCCESS = 4
00094 int32 result
00095
00096
00097 ================================================================================
00098 MSG: tabletop_object_detector/Table
00099 # Informs that a planar table has been detected at a given location
00100
00101 # The pose gives you the transform that take you to the coordinate system
00102 # of the table, with the origin somewhere in the table plane and the
00103 # z axis normal to the plane
00104 geometry_msgs/PoseStamped pose
00105
00106 # These values give you the observed extents of the table, along x and y,
00107 # in the table's own coordinate system (above)
00108 # there is no guarantee that the origin of the table coordinate system is
00109 # inside the boundary defined by these values.
00110 float32 x_min
00111 float32 x_max
00112 float32 y_min
00113 float32 y_max
00114
00115 # There is no guarantee that the table doe NOT extend further than these
00116 # values; this is just as far as we've observed it.
00117
00118 ================================================================================
00119 MSG: geometry_msgs/PoseStamped
00120 # A Pose with reference coordinate frame and timestamp
00121 Header header
00122 Pose pose
00123
00124 ================================================================================
00125 MSG: geometry_msgs/Pose
00126 # A representation of pose in free space, composed of postion and orientation.
00127 Point position
00128 Quaternion orientation
00129
00130 ================================================================================
00131 MSG: geometry_msgs/Point
00132 # This contains the position of a point in free space
00133 float64 x
00134 float64 y
00135 float64 z
00136
00137 ================================================================================
00138 MSG: geometry_msgs/Quaternion
00139 # This represents an orientation in free space in quaternion form.
00140
00141 float64 x
00142 float64 y
00143 float64 z
00144 float64 w
00145
00146 ================================================================================
00147 MSG: sensor_msgs/PointCloud
00148 # This message holds a collection of 3d points, plus optional additional
00149 # information about each point.
00150
00151 # Time of sensor data acquisition, coordinate frame ID.
00152 Header header
00153
00154 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00155 # in the frame given in the header.
00156 geometry_msgs/Point32[] points
00157
00158 # Each channel should have the same number of elements as points array,
00159 # and the data in each channel should correspond 1:1 with each point.
00160 # Channel names in common practice are listed in ChannelFloat32.msg.
00161 ChannelFloat32[] channels
00162
00163 ================================================================================
00164 MSG: geometry_msgs/Point32
00165 # This contains the position of a point in free space(with 32 bits of precision).
00166 # It is recommeded to use Point wherever possible instead of Point32.
00167 #
00168 # This recommendation is to promote interoperability.
00169 #
00170 # This message is designed to take up less space when sending
00171 # lots of points at once, as in the case of a PointCloud.
00172
00173 float32 x
00174 float32 y
00175 float32 z
00176 ================================================================================
00177 MSG: sensor_msgs/ChannelFloat32
00178 # This message is used by the PointCloud message to hold optional data
00179 # associated with each point in the cloud. The length of the values
00180 # array should be the same as the length of the points array in the
00181 # PointCloud, and each value should be associated with the corresponding
00182 # point.
00183
00184 # Channel names in existing practice include:
00185 # "u", "v" - row and column (respectively) in the left stereo image.
00186 # This is opposite to usual conventions but remains for
00187 # historical reasons. The newer PointCloud2 message has no
00188 # such problem.
00189 # "rgb" - For point clouds produced by color stereo cameras. uint8
00190 # (R,G,B) values packed into the least significant 24 bits,
00191 # in order.
00192 # "intensity" - laser or pixel intensity.
00193 # "distance"
00194
00195 # The channel name should give semantics of the channel (e.g.
00196 # "intensity" instead of "value").
00197 string name
00198
00199 # The values array should be 1-1 with the elements of the associated
00200 # PointCloud.
00201 float32[] values
00202
00203 """
00204 __slots__ = ['header','status','result']
00205 _slot_types = ['Header','actionlib_msgs/GoalStatus','object_segmentation_gui/ObjectSegmentationGuiResult']
00206
00207 def __init__(self, *args, **kwds):
00208 """
00209 Constructor. Any message fields that are implicitly/explicitly
00210 set to None will be assigned a default value. The recommend
00211 use is keyword arguments as this is more robust to future message
00212 changes. You cannot mix in-order arguments and keyword arguments.
00213
00214 The available fields are:
00215 header,status,result
00216
00217 @param args: complete set of field values, in .msg order
00218 @param kwds: use keyword arguments corresponding to message field names
00219 to set specific fields.
00220 """
00221 if args or kwds:
00222 super(ObjectSegmentationGuiActionResult, self).__init__(*args, **kwds)
00223 #message fields cannot be None, assign default values for those that are
00224 if self.header is None:
00225 self.header = std_msgs.msg._Header.Header()
00226 if self.status is None:
00227 self.status = actionlib_msgs.msg.GoalStatus()
00228 if self.result is None:
00229 self.result = object_segmentation_gui.msg.ObjectSegmentationGuiResult()
00230 else:
00231 self.header = std_msgs.msg._Header.Header()
00232 self.status = actionlib_msgs.msg.GoalStatus()
00233 self.result = object_segmentation_gui.msg.ObjectSegmentationGuiResult()
00234
00235 def _get_types(self):
00236 """
00237 internal API method
00238 """
00239 return self._slot_types
00240
00241 def serialize(self, buff):
00242 """
00243 serialize message into buffer
00244 @param buff: buffer
00245 @type buff: StringIO
00246 """
00247 try:
00248 _x = self
00249 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00250 _x = self.header.frame_id
00251 length = len(_x)
00252 buff.write(struct.pack('<I%ss'%length, length, _x))
00253 _x = self
00254 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00255 _x = self.status.goal_id.id
00256 length = len(_x)
00257 buff.write(struct.pack('<I%ss'%length, length, _x))
00258 buff.write(_struct_B.pack(self.status.status))
00259 _x = self.status.text
00260 length = len(_x)
00261 buff.write(struct.pack('<I%ss'%length, length, _x))
00262 _x = self
00263 buff.write(_struct_3I.pack(_x.result.table.pose.header.seq, _x.result.table.pose.header.stamp.secs, _x.result.table.pose.header.stamp.nsecs))
00264 _x = self.result.table.pose.header.frame_id
00265 length = len(_x)
00266 buff.write(struct.pack('<I%ss'%length, length, _x))
00267 _x = self
00268 buff.write(_struct_7d4f.pack(_x.result.table.pose.pose.position.x, _x.result.table.pose.pose.position.y, _x.result.table.pose.pose.position.z, _x.result.table.pose.pose.orientation.x, _x.result.table.pose.pose.orientation.y, _x.result.table.pose.pose.orientation.z, _x.result.table.pose.pose.orientation.w, _x.result.table.x_min, _x.result.table.x_max, _x.result.table.y_min, _x.result.table.y_max))
00269 length = len(self.result.clusters)
00270 buff.write(_struct_I.pack(length))
00271 for val1 in self.result.clusters:
00272 _v1 = val1.header
00273 buff.write(_struct_I.pack(_v1.seq))
00274 _v2 = _v1.stamp
00275 _x = _v2
00276 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00277 _x = _v1.frame_id
00278 length = len(_x)
00279 buff.write(struct.pack('<I%ss'%length, length, _x))
00280 length = len(val1.points)
00281 buff.write(_struct_I.pack(length))
00282 for val2 in val1.points:
00283 _x = val2
00284 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00285 length = len(val1.channels)
00286 buff.write(_struct_I.pack(length))
00287 for val2 in val1.channels:
00288 _x = val2.name
00289 length = len(_x)
00290 buff.write(struct.pack('<I%ss'%length, length, _x))
00291 length = len(val2.values)
00292 buff.write(_struct_I.pack(length))
00293 pattern = '<%sf'%length
00294 buff.write(struct.pack(pattern, *val2.values))
00295 buff.write(_struct_i.pack(self.result.result))
00296 except struct.error, se: self._check_types(se)
00297 except TypeError, te: self._check_types(te)
00298
00299 def deserialize(self, str):
00300 """
00301 unpack serialized message in str into this message instance
00302 @param str: byte array of serialized message
00303 @type str: str
00304 """
00305 try:
00306 if self.header is None:
00307 self.header = std_msgs.msg._Header.Header()
00308 if self.status is None:
00309 self.status = actionlib_msgs.msg.GoalStatus()
00310 if self.result is None:
00311 self.result = object_segmentation_gui.msg.ObjectSegmentationGuiResult()
00312 end = 0
00313 _x = self
00314 start = end
00315 end += 12
00316 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00317 start = end
00318 end += 4
00319 (length,) = _struct_I.unpack(str[start:end])
00320 start = end
00321 end += length
00322 self.header.frame_id = str[start:end]
00323 _x = self
00324 start = end
00325 end += 8
00326 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00327 start = end
00328 end += 4
00329 (length,) = _struct_I.unpack(str[start:end])
00330 start = end
00331 end += length
00332 self.status.goal_id.id = str[start:end]
00333 start = end
00334 end += 1
00335 (self.status.status,) = _struct_B.unpack(str[start:end])
00336 start = end
00337 end += 4
00338 (length,) = _struct_I.unpack(str[start:end])
00339 start = end
00340 end += length
00341 self.status.text = str[start:end]
00342 _x = self
00343 start = end
00344 end += 12
00345 (_x.result.table.pose.header.seq, _x.result.table.pose.header.stamp.secs, _x.result.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00346 start = end
00347 end += 4
00348 (length,) = _struct_I.unpack(str[start:end])
00349 start = end
00350 end += length
00351 self.result.table.pose.header.frame_id = str[start:end]
00352 _x = self
00353 start = end
00354 end += 72
00355 (_x.result.table.pose.pose.position.x, _x.result.table.pose.pose.position.y, _x.result.table.pose.pose.position.z, _x.result.table.pose.pose.orientation.x, _x.result.table.pose.pose.orientation.y, _x.result.table.pose.pose.orientation.z, _x.result.table.pose.pose.orientation.w, _x.result.table.x_min, _x.result.table.x_max, _x.result.table.y_min, _x.result.table.y_max,) = _struct_7d4f.unpack(str[start:end])
00356 start = end
00357 end += 4
00358 (length,) = _struct_I.unpack(str[start:end])
00359 self.result.clusters = []
00360 for i in xrange(0, length):
00361 val1 = sensor_msgs.msg.PointCloud()
00362 _v3 = val1.header
00363 start = end
00364 end += 4
00365 (_v3.seq,) = _struct_I.unpack(str[start:end])
00366 _v4 = _v3.stamp
00367 _x = _v4
00368 start = end
00369 end += 8
00370 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00371 start = end
00372 end += 4
00373 (length,) = _struct_I.unpack(str[start:end])
00374 start = end
00375 end += length
00376 _v3.frame_id = str[start:end]
00377 start = end
00378 end += 4
00379 (length,) = _struct_I.unpack(str[start:end])
00380 val1.points = []
00381 for i in xrange(0, length):
00382 val2 = geometry_msgs.msg.Point32()
00383 _x = val2
00384 start = end
00385 end += 12
00386 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00387 val1.points.append(val2)
00388 start = end
00389 end += 4
00390 (length,) = _struct_I.unpack(str[start:end])
00391 val1.channels = []
00392 for i in xrange(0, length):
00393 val2 = sensor_msgs.msg.ChannelFloat32()
00394 start = end
00395 end += 4
00396 (length,) = _struct_I.unpack(str[start:end])
00397 start = end
00398 end += length
00399 val2.name = str[start:end]
00400 start = end
00401 end += 4
00402 (length,) = _struct_I.unpack(str[start:end])
00403 pattern = '<%sf'%length
00404 start = end
00405 end += struct.calcsize(pattern)
00406 val2.values = struct.unpack(pattern, str[start:end])
00407 val1.channels.append(val2)
00408 self.result.clusters.append(val1)
00409 start = end
00410 end += 4
00411 (self.result.result,) = _struct_i.unpack(str[start:end])
00412 return self
00413 except struct.error, e:
00414 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00415
00416
00417 def serialize_numpy(self, buff, numpy):
00418 """
00419 serialize message with numpy array types into buffer
00420 @param buff: buffer
00421 @type buff: StringIO
00422 @param numpy: numpy python module
00423 @type numpy module
00424 """
00425 try:
00426 _x = self
00427 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs))
00428 _x = self.header.frame_id
00429 length = len(_x)
00430 buff.write(struct.pack('<I%ss'%length, length, _x))
00431 _x = self
00432 buff.write(_struct_2I.pack(_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs))
00433 _x = self.status.goal_id.id
00434 length = len(_x)
00435 buff.write(struct.pack('<I%ss'%length, length, _x))
00436 buff.write(_struct_B.pack(self.status.status))
00437 _x = self.status.text
00438 length = len(_x)
00439 buff.write(struct.pack('<I%ss'%length, length, _x))
00440 _x = self
00441 buff.write(_struct_3I.pack(_x.result.table.pose.header.seq, _x.result.table.pose.header.stamp.secs, _x.result.table.pose.header.stamp.nsecs))
00442 _x = self.result.table.pose.header.frame_id
00443 length = len(_x)
00444 buff.write(struct.pack('<I%ss'%length, length, _x))
00445 _x = self
00446 buff.write(_struct_7d4f.pack(_x.result.table.pose.pose.position.x, _x.result.table.pose.pose.position.y, _x.result.table.pose.pose.position.z, _x.result.table.pose.pose.orientation.x, _x.result.table.pose.pose.orientation.y, _x.result.table.pose.pose.orientation.z, _x.result.table.pose.pose.orientation.w, _x.result.table.x_min, _x.result.table.x_max, _x.result.table.y_min, _x.result.table.y_max))
00447 length = len(self.result.clusters)
00448 buff.write(_struct_I.pack(length))
00449 for val1 in self.result.clusters:
00450 _v5 = val1.header
00451 buff.write(_struct_I.pack(_v5.seq))
00452 _v6 = _v5.stamp
00453 _x = _v6
00454 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00455 _x = _v5.frame_id
00456 length = len(_x)
00457 buff.write(struct.pack('<I%ss'%length, length, _x))
00458 length = len(val1.points)
00459 buff.write(_struct_I.pack(length))
00460 for val2 in val1.points:
00461 _x = val2
00462 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00463 length = len(val1.channels)
00464 buff.write(_struct_I.pack(length))
00465 for val2 in val1.channels:
00466 _x = val2.name
00467 length = len(_x)
00468 buff.write(struct.pack('<I%ss'%length, length, _x))
00469 length = len(val2.values)
00470 buff.write(_struct_I.pack(length))
00471 pattern = '<%sf'%length
00472 buff.write(val2.values.tostring())
00473 buff.write(_struct_i.pack(self.result.result))
00474 except struct.error, se: self._check_types(se)
00475 except TypeError, te: self._check_types(te)
00476
00477 def deserialize_numpy(self, str, numpy):
00478 """
00479 unpack serialized message in str into this message instance using numpy for array types
00480 @param str: byte array of serialized message
00481 @type str: str
00482 @param numpy: numpy python module
00483 @type numpy: module
00484 """
00485 try:
00486 if self.header is None:
00487 self.header = std_msgs.msg._Header.Header()
00488 if self.status is None:
00489 self.status = actionlib_msgs.msg.GoalStatus()
00490 if self.result is None:
00491 self.result = object_segmentation_gui.msg.ObjectSegmentationGuiResult()
00492 end = 0
00493 _x = self
00494 start = end
00495 end += 12
00496 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00497 start = end
00498 end += 4
00499 (length,) = _struct_I.unpack(str[start:end])
00500 start = end
00501 end += length
00502 self.header.frame_id = str[start:end]
00503 _x = self
00504 start = end
00505 end += 8
00506 (_x.status.goal_id.stamp.secs, _x.status.goal_id.stamp.nsecs,) = _struct_2I.unpack(str[start:end])
00507 start = end
00508 end += 4
00509 (length,) = _struct_I.unpack(str[start:end])
00510 start = end
00511 end += length
00512 self.status.goal_id.id = str[start:end]
00513 start = end
00514 end += 1
00515 (self.status.status,) = _struct_B.unpack(str[start:end])
00516 start = end
00517 end += 4
00518 (length,) = _struct_I.unpack(str[start:end])
00519 start = end
00520 end += length
00521 self.status.text = str[start:end]
00522 _x = self
00523 start = end
00524 end += 12
00525 (_x.result.table.pose.header.seq, _x.result.table.pose.header.stamp.secs, _x.result.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00526 start = end
00527 end += 4
00528 (length,) = _struct_I.unpack(str[start:end])
00529 start = end
00530 end += length
00531 self.result.table.pose.header.frame_id = str[start:end]
00532 _x = self
00533 start = end
00534 end += 72
00535 (_x.result.table.pose.pose.position.x, _x.result.table.pose.pose.position.y, _x.result.table.pose.pose.position.z, _x.result.table.pose.pose.orientation.x, _x.result.table.pose.pose.orientation.y, _x.result.table.pose.pose.orientation.z, _x.result.table.pose.pose.orientation.w, _x.result.table.x_min, _x.result.table.x_max, _x.result.table.y_min, _x.result.table.y_max,) = _struct_7d4f.unpack(str[start:end])
00536 start = end
00537 end += 4
00538 (length,) = _struct_I.unpack(str[start:end])
00539 self.result.clusters = []
00540 for i in xrange(0, length):
00541 val1 = sensor_msgs.msg.PointCloud()
00542 _v7 = val1.header
00543 start = end
00544 end += 4
00545 (_v7.seq,) = _struct_I.unpack(str[start:end])
00546 _v8 = _v7.stamp
00547 _x = _v8
00548 start = end
00549 end += 8
00550 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00551 start = end
00552 end += 4
00553 (length,) = _struct_I.unpack(str[start:end])
00554 start = end
00555 end += length
00556 _v7.frame_id = str[start:end]
00557 start = end
00558 end += 4
00559 (length,) = _struct_I.unpack(str[start:end])
00560 val1.points = []
00561 for i in xrange(0, length):
00562 val2 = geometry_msgs.msg.Point32()
00563 _x = val2
00564 start = end
00565 end += 12
00566 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00567 val1.points.append(val2)
00568 start = end
00569 end += 4
00570 (length,) = _struct_I.unpack(str[start:end])
00571 val1.channels = []
00572 for i in xrange(0, length):
00573 val2 = sensor_msgs.msg.ChannelFloat32()
00574 start = end
00575 end += 4
00576 (length,) = _struct_I.unpack(str[start:end])
00577 start = end
00578 end += length
00579 val2.name = str[start:end]
00580 start = end
00581 end += 4
00582 (length,) = _struct_I.unpack(str[start:end])
00583 pattern = '<%sf'%length
00584 start = end
00585 end += struct.calcsize(pattern)
00586 val2.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00587 val1.channels.append(val2)
00588 self.result.clusters.append(val1)
00589 start = end
00590 end += 4
00591 (self.result.result,) = _struct_i.unpack(str[start:end])
00592 return self
00593 except struct.error, e:
00594 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00595
00596 _struct_I = roslib.message.struct_I
00597 _struct_B = struct.Struct("<B")
00598 _struct_7d4f = struct.Struct("<7d4f")
00599 _struct_2I = struct.Struct("<2I")
00600 _struct_i = struct.Struct("<i")
00601 _struct_3I = struct.Struct("<3I")
00602 _struct_3f = struct.Struct("<3f")