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