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