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