$search
00001 """autogenerated by genmsg_py from TableObject.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import std_msgs.msg 00006 import geometry_msgs.msg 00007 import sensor_msgs.msg 00008 00009 class TableObject(roslib.message.Message): 00010 _md5sum = "3ce72124397384b196976e00d07c3482" 00011 _type = "ias_table_msgs/TableObject" 00012 _has_header = False #flag to mark the presence of a Header object 00013 _full_text = """geometry_msgs/Point32 center 00014 geometry_msgs/Point32 min_bound 00015 geometry_msgs/Point32 max_bound 00016 00017 uint64 object_cop_id 00018 uint64 lo_id 00019 00020 sensor_msgs/PointCloud points 00021 sensor_msgs/Image roi 00022 00023 string perception_method 00024 string sensor_type 00025 string object_type 00026 string object_color 00027 string object_geometric_type 00028 uint64 table_id 00029 00030 ================================================================================ 00031 MSG: geometry_msgs/Point32 00032 # This contains the position of a point in free space(with 32 bits of precision). 00033 # It is recommeded to use Point wherever possible instead of Point32. 00034 # 00035 # This recommendation is to promote interoperability. 00036 # 00037 # This message is designed to take up less space when sending 00038 # lots of points at once, as in the case of a PointCloud. 00039 00040 float32 x 00041 float32 y 00042 float32 z 00043 ================================================================================ 00044 MSG: sensor_msgs/PointCloud 00045 # This message holds a collection of 3d points, plus optional additional 00046 # information about each point. 00047 00048 # Time of sensor data acquisition, coordinate frame ID. 00049 Header header 00050 00051 # Array of 3d points. Each Point32 should be interpreted as a 3d point 00052 # in the frame given in the header. 00053 geometry_msgs/Point32[] points 00054 00055 # Each channel should have the same number of elements as points array, 00056 # and the data in each channel should correspond 1:1 with each point. 00057 # Channel names in common practice are listed in ChannelFloat32.msg. 00058 ChannelFloat32[] channels 00059 00060 ================================================================================ 00061 MSG: std_msgs/Header 00062 # Standard metadata for higher-level stamped data types. 00063 # This is generally used to communicate timestamped data 00064 # in a particular coordinate frame. 00065 # 00066 # sequence ID: consecutively increasing ID 00067 uint32 seq 00068 #Two-integer timestamp that is expressed as: 00069 # * stamp.secs: seconds (stamp_secs) since epoch 00070 # * stamp.nsecs: nanoseconds since stamp_secs 00071 # time-handling sugar is provided by the client library 00072 time stamp 00073 #Frame this data is associated with 00074 # 0: no frame 00075 # 1: global frame 00076 string frame_id 00077 00078 ================================================================================ 00079 MSG: sensor_msgs/ChannelFloat32 00080 # This message is used by the PointCloud message to hold optional data 00081 # associated with each point in the cloud. The length of the values 00082 # array should be the same as the length of the points array in the 00083 # PointCloud, and each value should be associated with the corresponding 00084 # point. 00085 00086 # Channel names in existing practice include: 00087 # "u", "v" - row and column (respectively) in the left stereo image. 00088 # This is opposite to usual conventions but remains for 00089 # historical reasons. The newer PointCloud2 message has no 00090 # such problem. 00091 # "rgb" - For point clouds produced by color stereo cameras. uint8 00092 # (R,G,B) values packed into the least significant 24 bits, 00093 # in order. 00094 # "intensity" - laser or pixel intensity. 00095 # "distance" 00096 00097 # The channel name should give semantics of the channel (e.g. 00098 # "intensity" instead of "value"). 00099 string name 00100 00101 # The values array should be 1-1 with the elements of the associated 00102 # PointCloud. 00103 float32[] values 00104 00105 ================================================================================ 00106 MSG: sensor_msgs/Image 00107 # This message contains an uncompressed image 00108 # (0, 0) is at top-left corner of image 00109 # 00110 00111 Header header # Header timestamp should be acquisition time of image 00112 # Header frame_id should be optical frame of camera 00113 # origin of frame should be optical center of cameara 00114 # +x should point to the right in the image 00115 # +y should point down in the image 00116 # +z should point into to plane of the image 00117 # If the frame_id here and the frame_id of the CameraInfo 00118 # message associated with the image conflict 00119 # the behavior is undefined 00120 00121 uint32 height # image height, that is, number of rows 00122 uint32 width # image width, that is, number of columns 00123 00124 # The legal values for encoding are in file src/image_encodings.cpp 00125 # If you want to standardize a new string format, join 00126 # ros-users@lists.sourceforge.net and send an email proposing a new encoding. 00127 00128 string encoding # Encoding of pixels -- channel meaning, ordering, size 00129 # taken from the list of strings in src/image_encodings.cpp 00130 00131 uint8 is_bigendian # is this data bigendian? 00132 uint32 step # Full row length in bytes 00133 uint8[] data # actual matrix data, size is (step * rows) 00134 00135 """ 00136 __slots__ = ['center','min_bound','max_bound','object_cop_id','lo_id','points','roi','perception_method','sensor_type','object_type','object_color','object_geometric_type','table_id'] 00137 _slot_types = ['geometry_msgs/Point32','geometry_msgs/Point32','geometry_msgs/Point32','uint64','uint64','sensor_msgs/PointCloud','sensor_msgs/Image','string','string','string','string','string','uint64'] 00138 00139 def __init__(self, *args, **kwds): 00140 """ 00141 Constructor. Any message fields that are implicitly/explicitly 00142 set to None will be assigned a default value. The recommend 00143 use is keyword arguments as this is more robust to future message 00144 changes. You cannot mix in-order arguments and keyword arguments. 00145 00146 The available fields are: 00147 center,min_bound,max_bound,object_cop_id,lo_id,points,roi,perception_method,sensor_type,object_type,object_color,object_geometric_type,table_id 00148 00149 @param args: complete set of field values, in .msg order 00150 @param kwds: use keyword arguments corresponding to message field names 00151 to set specific fields. 00152 """ 00153 if args or kwds: 00154 super(TableObject, self).__init__(*args, **kwds) 00155 #message fields cannot be None, assign default values for those that are 00156 if self.center is None: 00157 self.center = geometry_msgs.msg.Point32() 00158 if self.min_bound is None: 00159 self.min_bound = geometry_msgs.msg.Point32() 00160 if self.max_bound is None: 00161 self.max_bound = geometry_msgs.msg.Point32() 00162 if self.object_cop_id is None: 00163 self.object_cop_id = 0 00164 if self.lo_id is None: 00165 self.lo_id = 0 00166 if self.points is None: 00167 self.points = sensor_msgs.msg.PointCloud() 00168 if self.roi is None: 00169 self.roi = sensor_msgs.msg.Image() 00170 if self.perception_method is None: 00171 self.perception_method = '' 00172 if self.sensor_type is None: 00173 self.sensor_type = '' 00174 if self.object_type is None: 00175 self.object_type = '' 00176 if self.object_color is None: 00177 self.object_color = '' 00178 if self.object_geometric_type is None: 00179 self.object_geometric_type = '' 00180 if self.table_id is None: 00181 self.table_id = 0 00182 else: 00183 self.center = geometry_msgs.msg.Point32() 00184 self.min_bound = geometry_msgs.msg.Point32() 00185 self.max_bound = geometry_msgs.msg.Point32() 00186 self.object_cop_id = 0 00187 self.lo_id = 0 00188 self.points = sensor_msgs.msg.PointCloud() 00189 self.roi = sensor_msgs.msg.Image() 00190 self.perception_method = '' 00191 self.sensor_type = '' 00192 self.object_type = '' 00193 self.object_color = '' 00194 self.object_geometric_type = '' 00195 self.table_id = 0 00196 00197 def _get_types(self): 00198 """ 00199 internal API method 00200 """ 00201 return self._slot_types 00202 00203 def serialize(self, buff): 00204 """ 00205 serialize message into buffer 00206 @param buff: buffer 00207 @type buff: StringIO 00208 """ 00209 try: 00210 _x = self 00211 buff.write(_struct_9f2Q3I.pack(_x.center.x, _x.center.y, _x.center.z, _x.min_bound.x, _x.min_bound.y, _x.min_bound.z, _x.max_bound.x, _x.max_bound.y, _x.max_bound.z, _x.object_cop_id, _x.lo_id, _x.points.header.seq, _x.points.header.stamp.secs, _x.points.header.stamp.nsecs)) 00212 _x = self.points.header.frame_id 00213 length = len(_x) 00214 buff.write(struct.pack('<I%ss'%length, length, _x)) 00215 length = len(self.points.points) 00216 buff.write(_struct_I.pack(length)) 00217 for val1 in self.points.points: 00218 _x = val1 00219 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 00220 length = len(self.points.channels) 00221 buff.write(_struct_I.pack(length)) 00222 for val1 in self.points.channels: 00223 _x = val1.name 00224 length = len(_x) 00225 buff.write(struct.pack('<I%ss'%length, length, _x)) 00226 length = len(val1.values) 00227 buff.write(_struct_I.pack(length)) 00228 pattern = '<%sf'%length 00229 buff.write(struct.pack(pattern, *val1.values)) 00230 _x = self 00231 buff.write(_struct_3I.pack(_x.roi.header.seq, _x.roi.header.stamp.secs, _x.roi.header.stamp.nsecs)) 00232 _x = self.roi.header.frame_id 00233 length = len(_x) 00234 buff.write(struct.pack('<I%ss'%length, length, _x)) 00235 _x = self 00236 buff.write(_struct_2I.pack(_x.roi.height, _x.roi.width)) 00237 _x = self.roi.encoding 00238 length = len(_x) 00239 buff.write(struct.pack('<I%ss'%length, length, _x)) 00240 _x = self 00241 buff.write(_struct_BI.pack(_x.roi.is_bigendian, _x.roi.step)) 00242 _x = self.roi.data 00243 length = len(_x) 00244 # - if encoded as a list instead, serialize as bytes instead of string 00245 if type(_x) in [list, tuple]: 00246 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00247 else: 00248 buff.write(struct.pack('<I%ss'%length, length, _x)) 00249 _x = self.perception_method 00250 length = len(_x) 00251 buff.write(struct.pack('<I%ss'%length, length, _x)) 00252 _x = self.sensor_type 00253 length = len(_x) 00254 buff.write(struct.pack('<I%ss'%length, length, _x)) 00255 _x = self.object_type 00256 length = len(_x) 00257 buff.write(struct.pack('<I%ss'%length, length, _x)) 00258 _x = self.object_color 00259 length = len(_x) 00260 buff.write(struct.pack('<I%ss'%length, length, _x)) 00261 _x = self.object_geometric_type 00262 length = len(_x) 00263 buff.write(struct.pack('<I%ss'%length, length, _x)) 00264 buff.write(_struct_Q.pack(self.table_id)) 00265 except struct.error as se: self._check_types(se) 00266 except TypeError as te: self._check_types(te) 00267 00268 def deserialize(self, str): 00269 """ 00270 unpack serialized message in str into this message instance 00271 @param str: byte array of serialized message 00272 @type str: str 00273 """ 00274 try: 00275 if self.center is None: 00276 self.center = geometry_msgs.msg.Point32() 00277 if self.min_bound is None: 00278 self.min_bound = geometry_msgs.msg.Point32() 00279 if self.max_bound is None: 00280 self.max_bound = geometry_msgs.msg.Point32() 00281 if self.points is None: 00282 self.points = sensor_msgs.msg.PointCloud() 00283 if self.roi is None: 00284 self.roi = sensor_msgs.msg.Image() 00285 end = 0 00286 _x = self 00287 start = end 00288 end += 64 00289 (_x.center.x, _x.center.y, _x.center.z, _x.min_bound.x, _x.min_bound.y, _x.min_bound.z, _x.max_bound.x, _x.max_bound.y, _x.max_bound.z, _x.object_cop_id, _x.lo_id, _x.points.header.seq, _x.points.header.stamp.secs, _x.points.header.stamp.nsecs,) = _struct_9f2Q3I.unpack(str[start:end]) 00290 start = end 00291 end += 4 00292 (length,) = _struct_I.unpack(str[start:end]) 00293 start = end 00294 end += length 00295 self.points.header.frame_id = str[start:end] 00296 start = end 00297 end += 4 00298 (length,) = _struct_I.unpack(str[start:end]) 00299 self.points.points = [] 00300 for i in range(0, length): 00301 val1 = geometry_msgs.msg.Point32() 00302 _x = val1 00303 start = end 00304 end += 12 00305 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 00306 self.points.points.append(val1) 00307 start = end 00308 end += 4 00309 (length,) = _struct_I.unpack(str[start:end]) 00310 self.points.channels = [] 00311 for i in range(0, length): 00312 val1 = sensor_msgs.msg.ChannelFloat32() 00313 start = end 00314 end += 4 00315 (length,) = _struct_I.unpack(str[start:end]) 00316 start = end 00317 end += length 00318 val1.name = str[start:end] 00319 start = end 00320 end += 4 00321 (length,) = _struct_I.unpack(str[start:end]) 00322 pattern = '<%sf'%length 00323 start = end 00324 end += struct.calcsize(pattern) 00325 val1.values = struct.unpack(pattern, str[start:end]) 00326 self.points.channels.append(val1) 00327 _x = self 00328 start = end 00329 end += 12 00330 (_x.roi.header.seq, _x.roi.header.stamp.secs, _x.roi.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00331 start = end 00332 end += 4 00333 (length,) = _struct_I.unpack(str[start:end]) 00334 start = end 00335 end += length 00336 self.roi.header.frame_id = str[start:end] 00337 _x = self 00338 start = end 00339 end += 8 00340 (_x.roi.height, _x.roi.width,) = _struct_2I.unpack(str[start:end]) 00341 start = end 00342 end += 4 00343 (length,) = _struct_I.unpack(str[start:end]) 00344 start = end 00345 end += length 00346 self.roi.encoding = str[start:end] 00347 _x = self 00348 start = end 00349 end += 5 00350 (_x.roi.is_bigendian, _x.roi.step,) = _struct_BI.unpack(str[start:end]) 00351 start = end 00352 end += 4 00353 (length,) = _struct_I.unpack(str[start:end]) 00354 start = end 00355 end += length 00356 self.roi.data = str[start:end] 00357 start = end 00358 end += 4 00359 (length,) = _struct_I.unpack(str[start:end]) 00360 start = end 00361 end += length 00362 self.perception_method = str[start:end] 00363 start = end 00364 end += 4 00365 (length,) = _struct_I.unpack(str[start:end]) 00366 start = end 00367 end += length 00368 self.sensor_type = str[start:end] 00369 start = end 00370 end += 4 00371 (length,) = _struct_I.unpack(str[start:end]) 00372 start = end 00373 end += length 00374 self.object_type = 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.object_color = str[start:end] 00381 start = end 00382 end += 4 00383 (length,) = _struct_I.unpack(str[start:end]) 00384 start = end 00385 end += length 00386 self.object_geometric_type = str[start:end] 00387 start = end 00388 end += 8 00389 (self.table_id,) = _struct_Q.unpack(str[start:end]) 00390 return self 00391 except struct.error as e: 00392 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00393 00394 00395 def serialize_numpy(self, buff, numpy): 00396 """ 00397 serialize message with numpy array types into buffer 00398 @param buff: buffer 00399 @type buff: StringIO 00400 @param numpy: numpy python module 00401 @type numpy module 00402 """ 00403 try: 00404 _x = self 00405 buff.write(_struct_9f2Q3I.pack(_x.center.x, _x.center.y, _x.center.z, _x.min_bound.x, _x.min_bound.y, _x.min_bound.z, _x.max_bound.x, _x.max_bound.y, _x.max_bound.z, _x.object_cop_id, _x.lo_id, _x.points.header.seq, _x.points.header.stamp.secs, _x.points.header.stamp.nsecs)) 00406 _x = self.points.header.frame_id 00407 length = len(_x) 00408 buff.write(struct.pack('<I%ss'%length, length, _x)) 00409 length = len(self.points.points) 00410 buff.write(_struct_I.pack(length)) 00411 for val1 in self.points.points: 00412 _x = val1 00413 buff.write(_struct_3f.pack(_x.x, _x.y, _x.z)) 00414 length = len(self.points.channels) 00415 buff.write(_struct_I.pack(length)) 00416 for val1 in self.points.channels: 00417 _x = val1.name 00418 length = len(_x) 00419 buff.write(struct.pack('<I%ss'%length, length, _x)) 00420 length = len(val1.values) 00421 buff.write(_struct_I.pack(length)) 00422 pattern = '<%sf'%length 00423 buff.write(val1.values.tostring()) 00424 _x = self 00425 buff.write(_struct_3I.pack(_x.roi.header.seq, _x.roi.header.stamp.secs, _x.roi.header.stamp.nsecs)) 00426 _x = self.roi.header.frame_id 00427 length = len(_x) 00428 buff.write(struct.pack('<I%ss'%length, length, _x)) 00429 _x = self 00430 buff.write(_struct_2I.pack(_x.roi.height, _x.roi.width)) 00431 _x = self.roi.encoding 00432 length = len(_x) 00433 buff.write(struct.pack('<I%ss'%length, length, _x)) 00434 _x = self 00435 buff.write(_struct_BI.pack(_x.roi.is_bigendian, _x.roi.step)) 00436 _x = self.roi.data 00437 length = len(_x) 00438 # - if encoded as a list instead, serialize as bytes instead of string 00439 if type(_x) in [list, tuple]: 00440 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00441 else: 00442 buff.write(struct.pack('<I%ss'%length, length, _x)) 00443 _x = self.perception_method 00444 length = len(_x) 00445 buff.write(struct.pack('<I%ss'%length, length, _x)) 00446 _x = self.sensor_type 00447 length = len(_x) 00448 buff.write(struct.pack('<I%ss'%length, length, _x)) 00449 _x = self.object_type 00450 length = len(_x) 00451 buff.write(struct.pack('<I%ss'%length, length, _x)) 00452 _x = self.object_color 00453 length = len(_x) 00454 buff.write(struct.pack('<I%ss'%length, length, _x)) 00455 _x = self.object_geometric_type 00456 length = len(_x) 00457 buff.write(struct.pack('<I%ss'%length, length, _x)) 00458 buff.write(_struct_Q.pack(self.table_id)) 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.center is None: 00472 self.center = geometry_msgs.msg.Point32() 00473 if self.min_bound is None: 00474 self.min_bound = geometry_msgs.msg.Point32() 00475 if self.max_bound is None: 00476 self.max_bound = geometry_msgs.msg.Point32() 00477 if self.points is None: 00478 self.points = sensor_msgs.msg.PointCloud() 00479 if self.roi is None: 00480 self.roi = sensor_msgs.msg.Image() 00481 end = 0 00482 _x = self 00483 start = end 00484 end += 64 00485 (_x.center.x, _x.center.y, _x.center.z, _x.min_bound.x, _x.min_bound.y, _x.min_bound.z, _x.max_bound.x, _x.max_bound.y, _x.max_bound.z, _x.object_cop_id, _x.lo_id, _x.points.header.seq, _x.points.header.stamp.secs, _x.points.header.stamp.nsecs,) = _struct_9f2Q3I.unpack(str[start:end]) 00486 start = end 00487 end += 4 00488 (length,) = _struct_I.unpack(str[start:end]) 00489 start = end 00490 end += length 00491 self.points.header.frame_id = str[start:end] 00492 start = end 00493 end += 4 00494 (length,) = _struct_I.unpack(str[start:end]) 00495 self.points.points = [] 00496 for i in range(0, length): 00497 val1 = geometry_msgs.msg.Point32() 00498 _x = val1 00499 start = end 00500 end += 12 00501 (_x.x, _x.y, _x.z,) = _struct_3f.unpack(str[start:end]) 00502 self.points.points.append(val1) 00503 start = end 00504 end += 4 00505 (length,) = _struct_I.unpack(str[start:end]) 00506 self.points.channels = [] 00507 for i in range(0, length): 00508 val1 = sensor_msgs.msg.ChannelFloat32() 00509 start = end 00510 end += 4 00511 (length,) = _struct_I.unpack(str[start:end]) 00512 start = end 00513 end += length 00514 val1.name = str[start:end] 00515 start = end 00516 end += 4 00517 (length,) = _struct_I.unpack(str[start:end]) 00518 pattern = '<%sf'%length 00519 start = end 00520 end += struct.calcsize(pattern) 00521 val1.values = numpy.frombuffer(str[start:end], dtype=numpy.float32, count=length) 00522 self.points.channels.append(val1) 00523 _x = self 00524 start = end 00525 end += 12 00526 (_x.roi.header.seq, _x.roi.header.stamp.secs, _x.roi.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00527 start = end 00528 end += 4 00529 (length,) = _struct_I.unpack(str[start:end]) 00530 start = end 00531 end += length 00532 self.roi.header.frame_id = str[start:end] 00533 _x = self 00534 start = end 00535 end += 8 00536 (_x.roi.height, _x.roi.width,) = _struct_2I.unpack(str[start:end]) 00537 start = end 00538 end += 4 00539 (length,) = _struct_I.unpack(str[start:end]) 00540 start = end 00541 end += length 00542 self.roi.encoding = str[start:end] 00543 _x = self 00544 start = end 00545 end += 5 00546 (_x.roi.is_bigendian, _x.roi.step,) = _struct_BI.unpack(str[start:end]) 00547 start = end 00548 end += 4 00549 (length,) = _struct_I.unpack(str[start:end]) 00550 start = end 00551 end += length 00552 self.roi.data = str[start:end] 00553 start = end 00554 end += 4 00555 (length,) = _struct_I.unpack(str[start:end]) 00556 start = end 00557 end += length 00558 self.perception_method = str[start:end] 00559 start = end 00560 end += 4 00561 (length,) = _struct_I.unpack(str[start:end]) 00562 start = end 00563 end += length 00564 self.sensor_type = str[start:end] 00565 start = end 00566 end += 4 00567 (length,) = _struct_I.unpack(str[start:end]) 00568 start = end 00569 end += length 00570 self.object_type = str[start:end] 00571 start = end 00572 end += 4 00573 (length,) = _struct_I.unpack(str[start:end]) 00574 start = end 00575 end += length 00576 self.object_color = str[start:end] 00577 start = end 00578 end += 4 00579 (length,) = _struct_I.unpack(str[start:end]) 00580 start = end 00581 end += length 00582 self.object_geometric_type = str[start:end] 00583 start = end 00584 end += 8 00585 (self.table_id,) = _struct_Q.unpack(str[start:end]) 00586 return self 00587 except struct.error as e: 00588 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00589 00590 _struct_I = roslib.message.struct_I 00591 _struct_9f2Q3I = struct.Struct("<9f2Q3I") 00592 _struct_BI = struct.Struct("<BI") 00593 _struct_2I = struct.Struct("<2I") 00594 _struct_Q = struct.Struct("<Q") 00595 _struct_3I = struct.Struct("<3I") 00596 _struct_3f = struct.Struct("<3f")