00001 """autogenerated by genmsg_py from TabletopDetectionResult.msg. Do not edit."""
00002 import roslib.message
00003 import struct
00004
00005 import tabletop_object_detector.msg
00006 import sensor_msgs.msg
00007 import geometry_msgs.msg
00008 import household_objects_database_msgs.msg
00009 import std_msgs.msg
00010
00011 class TabletopDetectionResult(roslib.message.Message):
00012 _md5sum = "52961ca508cc1f7a2b4e49033ee32175"
00013 _type = "tabletop_object_detector/TabletopDetectionResult"
00014 _has_header = False
00015 _full_text = """# Contains all the information from one run of the tabletop detection node
00016
00017 # The information for the plane that has been detected
00018 Table table
00019
00020 # The raw clusters detected in the scan
00021 sensor_msgs/PointCloud[] clusters
00022
00023 # The list of potential models that have been detected for each cluster
00024 # An empty list will be returned for a cluster that has no recognition results at all
00025 household_objects_database_msgs/DatabaseModelPoseList[] models
00026
00027 # For each cluster, the index of the list of models that was fit to that cluster
00028 # keep in mind that multiple raw clusters can correspond to a single fit
00029 int32[] cluster_model_indices
00030
00031 # Whether the detection has succeeded or failed
00032 int32 NO_CLOUD_RECEIVED = 1
00033 int32 NO_TABLE = 2
00034 int32 OTHER_ERROR = 3
00035 int32 SUCCESS = 4
00036 int32 result
00037
00038 ================================================================================
00039 MSG: tabletop_object_detector/Table
00040 # Informs that a planar table has been detected at a given location
00041
00042 # The pose gives you the transform that take you to the coordinate system
00043 # of the table, with the origin somewhere in the table plane and the
00044 # z axis normal to the plane
00045 geometry_msgs/PoseStamped pose
00046
00047 # These values give you the observed extents of the table, along x and y,
00048 # in the table's own coordinate system (above)
00049 # there is no guarantee that the origin of the table coordinate system is
00050 # inside the boundary defined by these values.
00051 float32 x_min
00052 float32 x_max
00053 float32 y_min
00054 float32 y_max
00055
00056 # There is no guarantee that the table doe NOT extend further than these
00057 # values; this is just as far as we've observed it.
00058
00059 ================================================================================
00060 MSG: geometry_msgs/PoseStamped
00061 # A Pose with reference coordinate frame and timestamp
00062 Header header
00063 Pose pose
00064
00065 ================================================================================
00066 MSG: std_msgs/Header
00067 # Standard metadata for higher-level stamped data types.
00068 # This is generally used to communicate timestamped data
00069 # in a particular coordinate frame.
00070 #
00071 # sequence ID: consecutively increasing ID
00072 uint32 seq
00073 #Two-integer timestamp that is expressed as:
00074 # * stamp.secs: seconds (stamp_secs) since epoch
00075 # * stamp.nsecs: nanoseconds since stamp_secs
00076 # time-handling sugar is provided by the client library
00077 time stamp
00078 #Frame this data is associated with
00079 # 0: no frame
00080 # 1: global frame
00081 string frame_id
00082
00083 ================================================================================
00084 MSG: geometry_msgs/Pose
00085 # A representation of pose in free space, composed of postion and orientation.
00086 Point position
00087 Quaternion orientation
00088
00089 ================================================================================
00090 MSG: geometry_msgs/Point
00091 # This contains the position of a point in free space
00092 float64 x
00093 float64 y
00094 float64 z
00095
00096 ================================================================================
00097 MSG: geometry_msgs/Quaternion
00098 # This represents an orientation in free space in quaternion form.
00099
00100 float64 x
00101 float64 y
00102 float64 z
00103 float64 w
00104
00105 ================================================================================
00106 MSG: sensor_msgs/PointCloud
00107 # This message holds a collection of 3d points, plus optional additional
00108 # information about each point.
00109
00110 # Time of sensor data acquisition, coordinate frame ID.
00111 Header header
00112
00113 # Array of 3d points. Each Point32 should be interpreted as a 3d point
00114 # in the frame given in the header.
00115 geometry_msgs/Point32[] points
00116
00117 # Each channel should have the same number of elements as points array,
00118 # and the data in each channel should correspond 1:1 with each point.
00119 # Channel names in common practice are listed in ChannelFloat32.msg.
00120 ChannelFloat32[] channels
00121
00122 ================================================================================
00123 MSG: geometry_msgs/Point32
00124 # This contains the position of a point in free space(with 32 bits of precision).
00125 # It is recommeded to use Point wherever possible instead of Point32.
00126 #
00127 # This recommendation is to promote interoperability.
00128 #
00129 # This message is designed to take up less space when sending
00130 # lots of points at once, as in the case of a PointCloud.
00131
00132 float32 x
00133 float32 y
00134 float32 z
00135 ================================================================================
00136 MSG: sensor_msgs/ChannelFloat32
00137 # This message is used by the PointCloud message to hold optional data
00138 # associated with each point in the cloud. The length of the values
00139 # array should be the same as the length of the points array in the
00140 # PointCloud, and each value should be associated with the corresponding
00141 # point.
00142
00143 # Channel names in existing practice include:
00144 # "u", "v" - row and column (respectively) in the left stereo image.
00145 # This is opposite to usual conventions but remains for
00146 # historical reasons. The newer PointCloud2 message has no
00147 # such problem.
00148 # "rgb" - For point clouds produced by color stereo cameras. uint8
00149 # (R,G,B) values packed into the least significant 24 bits,
00150 # in order.
00151 # "intensity" - laser or pixel intensity.
00152 # "distance"
00153
00154 # The channel name should give semantics of the channel (e.g.
00155 # "intensity" instead of "value").
00156 string name
00157
00158 # The values array should be 1-1 with the elements of the associated
00159 # PointCloud.
00160 float32[] values
00161
00162 ================================================================================
00163 MSG: household_objects_database_msgs/DatabaseModelPoseList
00164 # stores a list of possible database models recognition results
00165 DatabaseModelPose[] model_list
00166 ================================================================================
00167 MSG: household_objects_database_msgs/DatabaseModelPose
00168 # Informs that a specific model from the Model Database has been
00169 # identified at a certain location
00170
00171 # the database id of the model
00172 int32 model_id
00173
00174 # the pose that it can be found in
00175 geometry_msgs/PoseStamped pose
00176
00177 # a measure of the confidence level in this detection result
00178 float32 confidence
00179 """
00180 # Pseudo-constants
00181 NO_CLOUD_RECEIVED = 1
00182 NO_TABLE = 2
00183 OTHER_ERROR = 3
00184 SUCCESS = 4
00185
00186 __slots__ = ['table','clusters','models','cluster_model_indices','result']
00187 _slot_types = ['tabletop_object_detector/Table','sensor_msgs/PointCloud[]','household_objects_database_msgs/DatabaseModelPoseList[]','int32[]','int32']
00188
00189 def __init__(self, *args, **kwds):
00190 """
00191 Constructor. Any message fields that are implicitly/explicitly
00192 set to None will be assigned a default value. The recommend
00193 use is keyword arguments as this is more robust to future message
00194 changes. You cannot mix in-order arguments and keyword arguments.
00195
00196 The available fields are:
00197 table,clusters,models,cluster_model_indices,result
00198
00199 @param args: complete set of field values, in .msg order
00200 @param kwds: use keyword arguments corresponding to message field names
00201 to set specific fields.
00202 """
00203 if args or kwds:
00204 super(TabletopDetectionResult, self).__init__(*args, **kwds)
00205 #message fields cannot be None, assign default values for those that are
00206 if self.table is None:
00207 self.table = tabletop_object_detector.msg.Table()
00208 if self.clusters is None:
00209 self.clusters = []
00210 if self.models is None:
00211 self.models = []
00212 if self.cluster_model_indices is None:
00213 self.cluster_model_indices = []
00214 if self.result is None:
00215 self.result = 0
00216 else:
00217 self.table = tabletop_object_detector.msg.Table()
00218 self.clusters = []
00219 self.models = []
00220 self.cluster_model_indices = []
00221 self.result = 0
00222
00223 def _get_types(self):
00224 """
00225 internal API method
00226 """
00227 return self._slot_types
00228
00229 def serialize(self, buff):
00230 """
00231 serialize message into buffer
00232 @param buff: buffer
00233 @type buff: StringIO
00234 """
00235 try:
00236 _x = self
00237 buff.write(_struct_3I.pack(_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs))
00238 _x = self.table.pose.header.frame_id
00239 length = len(_x)
00240 buff.write(struct.pack('<I%ss'%length, length, _x))
00241 _x = self
00242 buff.write(_struct_7d4f.pack(_x.table.pose.pose.position.x, _x.table.pose.pose.position.y, _x.table.pose.pose.position.z, _x.table.pose.pose.orientation.x, _x.table.pose.pose.orientation.y, _x.table.pose.pose.orientation.z, _x.table.pose.pose.orientation.w, _x.table.x_min, _x.table.x_max, _x.table.y_min, _x.table.y_max))
00243 length = len(self.clusters)
00244 buff.write(_struct_I.pack(length))
00245 for val1 in self.clusters:
00246 _v1 = val1.header
00247 buff.write(_struct_I.pack(_v1.seq))
00248 _v2 = _v1.stamp
00249 _x = _v2
00250 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00251 _x = _v1.frame_id
00252 length = len(_x)
00253 buff.write(struct.pack('<I%ss'%length, length, _x))
00254 length = len(val1.points)
00255 buff.write(_struct_I.pack(length))
00256 for val2 in val1.points:
00257 _x = val2
00258 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00259 length = len(val1.channels)
00260 buff.write(_struct_I.pack(length))
00261 for val2 in val1.channels:
00262 _x = val2.name
00263 length = len(_x)
00264 buff.write(struct.pack('<I%ss'%length, length, _x))
00265 length = len(val2.values)
00266 buff.write(_struct_I.pack(length))
00267 pattern = '<%sf'%length
00268 buff.write(struct.pack(pattern, *val2.values))
00269 length = len(self.models)
00270 buff.write(_struct_I.pack(length))
00271 for val1 in self.models:
00272 length = len(val1.model_list)
00273 buff.write(_struct_I.pack(length))
00274 for val2 in val1.model_list:
00275 buff.write(_struct_i.pack(val2.model_id))
00276 _v3 = val2.pose
00277 _v4 = _v3.header
00278 buff.write(_struct_I.pack(_v4.seq))
00279 _v5 = _v4.stamp
00280 _x = _v5
00281 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00282 _x = _v4.frame_id
00283 length = len(_x)
00284 buff.write(struct.pack('<I%ss'%length, length, _x))
00285 _v6 = _v3.pose
00286 _v7 = _v6.position
00287 _x = _v7
00288 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00289 _v8 = _v6.orientation
00290 _x = _v8
00291 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00292 buff.write(_struct_f.pack(val2.confidence))
00293 length = len(self.cluster_model_indices)
00294 buff.write(_struct_I.pack(length))
00295 pattern = '<%si'%length
00296 buff.write(struct.pack(pattern, *self.cluster_model_indices))
00297 buff.write(_struct_i.pack(self.result))
00298 except struct.error, se: self._check_types(se)
00299 except TypeError, te: self._check_types(te)
00300
00301 def deserialize(self, str):
00302 """
00303 unpack serialized message in str into this message instance
00304 @param str: byte array of serialized message
00305 @type str: str
00306 """
00307 try:
00308 if self.table is None:
00309 self.table = tabletop_object_detector.msg.Table()
00310 end = 0
00311 _x = self
00312 start = end
00313 end += 12
00314 (_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00315 start = end
00316 end += 4
00317 (length,) = _struct_I.unpack(str[start:end])
00318 start = end
00319 end += length
00320 self.table.pose.header.frame_id = str[start:end]
00321 _x = self
00322 start = end
00323 end += 72
00324 (_x.table.pose.pose.position.x, _x.table.pose.pose.position.y, _x.table.pose.pose.position.z, _x.table.pose.pose.orientation.x, _x.table.pose.pose.orientation.y, _x.table.pose.pose.orientation.z, _x.table.pose.pose.orientation.w, _x.table.x_min, _x.table.x_max, _x.table.y_min, _x.table.y_max,) = _struct_7d4f.unpack(str[start:end])
00325 start = end
00326 end += 4
00327 (length,) = _struct_I.unpack(str[start:end])
00328 self.clusters = []
00329 for i in xrange(0, length):
00330 val1 = sensor_msgs.msg.PointCloud()
00331 _v9 = val1.header
00332 start = end
00333 end += 4
00334 (_v9.seq,) = _struct_I.unpack(str[start:end])
00335 _v10 = _v9.stamp
00336 _x = _v10
00337 start = end
00338 end += 8
00339 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00340 start = end
00341 end += 4
00342 (length,) = _struct_I.unpack(str[start:end])
00343 start = end
00344 end += length
00345 _v9.frame_id = str[start:end]
00346 start = end
00347 end += 4
00348 (length,) = _struct_I.unpack(str[start:end])
00349 val1.points = []
00350 for i in xrange(0, length):
00351 val2 = geometry_msgs.msg.Point32()
00352 _x = val2
00353 start = end
00354 end += 12
00355 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00356 val1.points.append(val2)
00357 start = end
00358 end += 4
00359 (length,) = _struct_I.unpack(str[start:end])
00360 val1.channels = []
00361 for i in xrange(0, length):
00362 val2 = sensor_msgs.msg.ChannelFloat32()
00363 start = end
00364 end += 4
00365 (length,) = _struct_I.unpack(str[start:end])
00366 start = end
00367 end += length
00368 val2.name = str[start:end]
00369 start = end
00370 end += 4
00371 (length,) = _struct_I.unpack(str[start:end])
00372 pattern = '<%sf'%length
00373 start = end
00374 end += struct.calcsize(pattern)
00375 val2.values = struct.unpack(pattern, str[start:end])
00376 val1.channels.append(val2)
00377 self.clusters.append(val1)
00378 start = end
00379 end += 4
00380 (length,) = _struct_I.unpack(str[start:end])
00381 self.models = []
00382 for i in xrange(0, length):
00383 val1 = household_objects_database_msgs.msg.DatabaseModelPoseList()
00384 start = end
00385 end += 4
00386 (length,) = _struct_I.unpack(str[start:end])
00387 val1.model_list = []
00388 for i in xrange(0, length):
00389 val2 = household_objects_database_msgs.msg.DatabaseModelPose()
00390 start = end
00391 end += 4
00392 (val2.model_id,) = _struct_i.unpack(str[start:end])
00393 _v11 = val2.pose
00394 _v12 = _v11.header
00395 start = end
00396 end += 4
00397 (_v12.seq,) = _struct_I.unpack(str[start:end])
00398 _v13 = _v12.stamp
00399 _x = _v13
00400 start = end
00401 end += 8
00402 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00403 start = end
00404 end += 4
00405 (length,) = _struct_I.unpack(str[start:end])
00406 start = end
00407 end += length
00408 _v12.frame_id = str[start:end]
00409 _v14 = _v11.pose
00410 _v15 = _v14.position
00411 _x = _v15
00412 start = end
00413 end += 24
00414 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00415 _v16 = _v14.orientation
00416 _x = _v16
00417 start = end
00418 end += 32
00419 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00420 start = end
00421 end += 4
00422 (val2.confidence,) = _struct_f.unpack(str[start:end])
00423 val1.model_list.append(val2)
00424 self.models.append(val1)
00425 start = end
00426 end += 4
00427 (length,) = _struct_I.unpack(str[start:end])
00428 pattern = '<%si'%length
00429 start = end
00430 end += struct.calcsize(pattern)
00431 self.cluster_model_indices = struct.unpack(pattern, str[start:end])
00432 start = end
00433 end += 4
00434 (self.result,) = _struct_i.unpack(str[start:end])
00435 return self
00436 except struct.error, e:
00437 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00438
00439
00440 def serialize_numpy(self, buff, numpy):
00441 """
00442 serialize message with numpy array types into buffer
00443 @param buff: buffer
00444 @type buff: StringIO
00445 @param numpy: numpy python module
00446 @type numpy module
00447 """
00448 try:
00449 _x = self
00450 buff.write(_struct_3I.pack(_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs))
00451 _x = self.table.pose.header.frame_id
00452 length = len(_x)
00453 buff.write(struct.pack('<I%ss'%length, length, _x))
00454 _x = self
00455 buff.write(_struct_7d4f.pack(_x.table.pose.pose.position.x, _x.table.pose.pose.position.y, _x.table.pose.pose.position.z, _x.table.pose.pose.orientation.x, _x.table.pose.pose.orientation.y, _x.table.pose.pose.orientation.z, _x.table.pose.pose.orientation.w, _x.table.x_min, _x.table.x_max, _x.table.y_min, _x.table.y_max))
00456 length = len(self.clusters)
00457 buff.write(_struct_I.pack(length))
00458 for val1 in self.clusters:
00459 _v17 = val1.header
00460 buff.write(_struct_I.pack(_v17.seq))
00461 _v18 = _v17.stamp
00462 _x = _v18
00463 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00464 _x = _v17.frame_id
00465 length = len(_x)
00466 buff.write(struct.pack('<I%ss'%length, length, _x))
00467 length = len(val1.points)
00468 buff.write(_struct_I.pack(length))
00469 for val2 in val1.points:
00470 _x = val2
00471 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z))
00472 length = len(val1.channels)
00473 buff.write(_struct_I.pack(length))
00474 for val2 in val1.channels:
00475 _x = val2.name
00476 length = len(_x)
00477 buff.write(struct.pack('<I%ss'%length, length, _x))
00478 length = len(val2.values)
00479 buff.write(_struct_I.pack(length))
00480 pattern = '<%sf'%length
00481 buff.write(val2.values.tostring())
00482 length = len(self.models)
00483 buff.write(_struct_I.pack(length))
00484 for val1 in self.models:
00485 length = len(val1.model_list)
00486 buff.write(_struct_I.pack(length))
00487 for val2 in val1.model_list:
00488 buff.write(_struct_i.pack(val2.model_id))
00489 _v19 = val2.pose
00490 _v20 = _v19.header
00491 buff.write(_struct_I.pack(_v20.seq))
00492 _v21 = _v20.stamp
00493 _x = _v21
00494 buff.write(_struct_2I.pack(_x.secs, _x.nsecs))
00495 _x = _v20.frame_id
00496 length = len(_x)
00497 buff.write(struct.pack('<I%ss'%length, length, _x))
00498 _v22 = _v19.pose
00499 _v23 = _v22.position
00500 _x = _v23
00501 buff.write(_struct_3d.pack(_x.x, _x.y, _x.z))
00502 _v24 = _v22.orientation
00503 _x = _v24
00504 buff.write(_struct_4d.pack(_x.x, _x.y, _x.z, _x.w))
00505 buff.write(_struct_f.pack(val2.confidence))
00506 length = len(self.cluster_model_indices)
00507 buff.write(_struct_I.pack(length))
00508 pattern = '<%si'%length
00509 buff.write(self.cluster_model_indices.tostring())
00510 buff.write(_struct_i.pack(self.result))
00511 except struct.error, se: self._check_types(se)
00512 except TypeError, te: self._check_types(te)
00513
00514 def deserialize_numpy(self, str, numpy):
00515 """
00516 unpack serialized message in str into this message instance using numpy for array types
00517 @param str: byte array of serialized message
00518 @type str: str
00519 @param numpy: numpy python module
00520 @type numpy: module
00521 """
00522 try:
00523 if self.table is None:
00524 self.table = tabletop_object_detector.msg.Table()
00525 end = 0
00526 _x = self
00527 start = end
00528 end += 12
00529 (_x.table.pose.header.seq, _x.table.pose.header.stamp.secs, _x.table.pose.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end])
00530 start = end
00531 end += 4
00532 (length,) = _struct_I.unpack(str[start:end])
00533 start = end
00534 end += length
00535 self.table.pose.header.frame_id = str[start:end]
00536 _x = self
00537 start = end
00538 end += 72
00539 (_x.table.pose.pose.position.x, _x.table.pose.pose.position.y, _x.table.pose.pose.position.z, _x.table.pose.pose.orientation.x, _x.table.pose.pose.orientation.y, _x.table.pose.pose.orientation.z, _x.table.pose.pose.orientation.w, _x.table.x_min, _x.table.x_max, _x.table.y_min, _x.table.y_max,) = _struct_7d4f.unpack(str[start:end])
00540 start = end
00541 end += 4
00542 (length,) = _struct_I.unpack(str[start:end])
00543 self.clusters = []
00544 for i in xrange(0, length):
00545 val1 = sensor_msgs.msg.PointCloud()
00546 _v25 = val1.header
00547 start = end
00548 end += 4
00549 (_v25.seq,) = _struct_I.unpack(str[start:end])
00550 _v26 = _v25.stamp
00551 _x = _v26
00552 start = end
00553 end += 8
00554 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00555 start = end
00556 end += 4
00557 (length,) = _struct_I.unpack(str[start:end])
00558 start = end
00559 end += length
00560 _v25.frame_id = str[start:end]
00561 start = end
00562 end += 4
00563 (length,) = _struct_I.unpack(str[start:end])
00564 val1.points = []
00565 for i in xrange(0, length):
00566 val2 = geometry_msgs.msg.Point32()
00567 _x = val2
00568 start = end
00569 end += 12
00570 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end])
00571 val1.points.append(val2)
00572 start = end
00573 end += 4
00574 (length,) = _struct_I.unpack(str[start:end])
00575 val1.channels = []
00576 for i in xrange(0, length):
00577 val2 = sensor_msgs.msg.ChannelFloat32()
00578 start = end
00579 end += 4
00580 (length,) = _struct_I.unpack(str[start:end])
00581 start = end
00582 end += length
00583 val2.name = str[start:end]
00584 start = end
00585 end += 4
00586 (length,) = _struct_I.unpack(str[start:end])
00587 pattern = '<%sf'%length
00588 start = end
00589 end += struct.calcsize(pattern)
00590 val2.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length)
00591 val1.channels.append(val2)
00592 self.clusters.append(val1)
00593 start = end
00594 end += 4
00595 (length,) = _struct_I.unpack(str[start:end])
00596 self.models = []
00597 for i in xrange(0, length):
00598 val1 = household_objects_database_msgs.msg.DatabaseModelPoseList()
00599 start = end
00600 end += 4
00601 (length,) = _struct_I.unpack(str[start:end])
00602 val1.model_list = []
00603 for i in xrange(0, length):
00604 val2 = household_objects_database_msgs.msg.DatabaseModelPose()
00605 start = end
00606 end += 4
00607 (val2.model_id,) = _struct_i.unpack(str[start:end])
00608 _v27 = val2.pose
00609 _v28 = _v27.header
00610 start = end
00611 end += 4
00612 (_v28.seq,) = _struct_I.unpack(str[start:end])
00613 _v29 = _v28.stamp
00614 _x = _v29
00615 start = end
00616 end += 8
00617 (_x.secs, _x.nsecs,) = _struct_2I.unpack(str[start:end])
00618 start = end
00619 end += 4
00620 (length,) = _struct_I.unpack(str[start:end])
00621 start = end
00622 end += length
00623 _v28.frame_id = str[start:end]
00624 _v30 = _v27.pose
00625 _v31 = _v30.position
00626 _x = _v31
00627 start = end
00628 end += 24
00629 (_x.x, _x.y, _x.z,) = _struct_3d.unpack(str[start:end])
00630 _v32 = _v30.orientation
00631 _x = _v32
00632 start = end
00633 end += 32
00634 (_x.x, _x.y, _x.z, _x.w,) = _struct_4d.unpack(str[start:end])
00635 start = end
00636 end += 4
00637 (val2.confidence,) = _struct_f.unpack(str[start:end])
00638 val1.model_list.append(val2)
00639 self.models.append(val1)
00640 start = end
00641 end += 4
00642 (length,) = _struct_I.unpack(str[start:end])
00643 pattern = '<%si'%length
00644 start = end
00645 end += struct.calcsize(pattern)
00646 self.cluster_model_indices = numpy.frombuffer(str[start:end], dtype=numpy.int32, count=length)
00647 start = end
00648 end += 4
00649 (self.result,) = _struct_i.unpack(str[start:end])
00650 return self
00651 except struct.error, e:
00652 raise roslib.message.DeserializationError(e) #most likely buffer underfill
00653
00654 _struct_I = roslib.message.struct_I
00655 _struct_7d4f = struct.Struct("<7d4f")
00656 _struct_f = struct.Struct("<f")
00657 _struct_2I = struct.Struct("<2I")
00658 _struct_i = struct.Struct("<i")
00659 _struct_3I = struct.Struct("<3I")
00660 _struct_4d = struct.Struct("<4d")
00661 _struct_3f = struct.Struct("<3f")
00662 _struct_3d = struct.Struct("<3d")