$search
00001 """autogenerated by genmsg_py from ImagePercept.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import sensor_msgs.msg 00006 import worldmodel_msgs.msg 00007 import std_msgs.msg 00008 00009 class ImagePercept(roslib.message.Message): 00010 _md5sum = "cfe1ba9ccbb3e43950b420f7336a3c6c" 00011 _type = "worldmodel_msgs/ImagePercept" 00012 _has_header = True #flag to mark the presence of a Header object 00013 _full_text = """# worldmodel_msgs/ImagePercept 00014 # This message represents an observation of an object in a single image. 00015 00016 # The header should equal the header of the corresponding image. 00017 Header header 00018 00019 # The camera info which is needed to project from image coordinates to world coordinates 00020 sensor_msgs/CameraInfo camera_info 00021 00022 # Center coordinates of the percept in image coordinates 00023 # x: axis points to the right in the image 00024 # y: axis points downward in the image 00025 float32 x 00026 float32 y 00027 00028 # Normalized size of the percept in image coordinates (or 0.0) 00029 float32 width 00030 float32 height 00031 00032 # Distance estimate (slope distance) (or 0.0) 00033 float32 distance 00034 00035 # Additional information about the percept 00036 worldmodel_msgs/PerceptInfo info 00037 00038 ================================================================================ 00039 MSG: std_msgs/Header 00040 # Standard metadata for higher-level stamped data types. 00041 # This is generally used to communicate timestamped data 00042 # in a particular coordinate frame. 00043 # 00044 # sequence ID: consecutively increasing ID 00045 uint32 seq 00046 #Two-integer timestamp that is expressed as: 00047 # * stamp.secs: seconds (stamp_secs) since epoch 00048 # * stamp.nsecs: nanoseconds since stamp_secs 00049 # time-handling sugar is provided by the client library 00050 time stamp 00051 #Frame this data is associated with 00052 # 0: no frame 00053 # 1: global frame 00054 string frame_id 00055 00056 ================================================================================ 00057 MSG: sensor_msgs/CameraInfo 00058 # This message defines meta information for a camera. It should be in a 00059 # camera namespace on topic "camera_info" and accompanied by up to five 00060 # image topics named: 00061 # 00062 # image_raw - raw data from the camera driver, possibly Bayer encoded 00063 # image - monochrome, distorted 00064 # image_color - color, distorted 00065 # image_rect - monochrome, rectified 00066 # image_rect_color - color, rectified 00067 # 00068 # The image_pipeline contains packages (image_proc, stereo_image_proc) 00069 # for producing the four processed image topics from image_raw and 00070 # camera_info. The meaning of the camera parameters are described in 00071 # detail at http://www.ros.org/wiki/image_pipeline/CameraInfo. 00072 # 00073 # The image_geometry package provides a user-friendly interface to 00074 # common operations using this meta information. If you want to, e.g., 00075 # project a 3d point into image coordinates, we strongly recommend 00076 # using image_geometry. 00077 # 00078 # If the camera is uncalibrated, the matrices D, K, R, P should be left 00079 # zeroed out. In particular, clients may assume that K[0] == 0.0 00080 # indicates an uncalibrated camera. 00081 00082 ####################################################################### 00083 # Image acquisition info # 00084 ####################################################################### 00085 00086 # Time of image acquisition, camera coordinate frame ID 00087 Header header # Header timestamp should be acquisition time of image 00088 # Header frame_id should be optical frame of camera 00089 # origin of frame should be optical center of camera 00090 # +x should point to the right in the image 00091 # +y should point down in the image 00092 # +z should point into the plane of the image 00093 00094 00095 ####################################################################### 00096 # Calibration Parameters # 00097 ####################################################################### 00098 # These are fixed during camera calibration. Their values will be the # 00099 # same in all messages until the camera is recalibrated. Note that # 00100 # self-calibrating systems may "recalibrate" frequently. # 00101 # # 00102 # The internal parameters can be used to warp a raw (distorted) image # 00103 # to: # 00104 # 1. An undistorted image (requires D and K) # 00105 # 2. A rectified image (requires D, K, R) # 00106 # The projection matrix P projects 3D points into the rectified image.# 00107 ####################################################################### 00108 00109 # The image dimensions with which the camera was calibrated. Normally 00110 # this will be the full camera resolution in pixels. 00111 uint32 height 00112 uint32 width 00113 00114 # The distortion model used. Supported models are listed in 00115 # sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a 00116 # simple model of radial and tangential distortion - is sufficent. 00117 string distortion_model 00118 00119 # The distortion parameters, size depending on the distortion model. 00120 # For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3). 00121 float64[] D 00122 00123 # Intrinsic camera matrix for the raw (distorted) images. 00124 # [fx 0 cx] 00125 # K = [ 0 fy cy] 00126 # [ 0 0 1] 00127 # Projects 3D points in the camera coordinate frame to 2D pixel 00128 # coordinates using the focal lengths (fx, fy) and principal point 00129 # (cx, cy). 00130 float64[9] K # 3x3 row-major matrix 00131 00132 # Rectification matrix (stereo cameras only) 00133 # A rotation matrix aligning the camera coordinate system to the ideal 00134 # stereo image plane so that epipolar lines in both stereo images are 00135 # parallel. 00136 float64[9] R # 3x3 row-major matrix 00137 00138 # Projection/camera matrix 00139 # [fx' 0 cx' Tx] 00140 # P = [ 0 fy' cy' Ty] 00141 # [ 0 0 1 0] 00142 # By convention, this matrix specifies the intrinsic (camera) matrix 00143 # of the processed (rectified) image. That is, the left 3x3 portion 00144 # is the normal camera intrinsic matrix for the rectified image. 00145 # It projects 3D points in the camera coordinate frame to 2D pixel 00146 # coordinates using the focal lengths (fx', fy') and principal point 00147 # (cx', cy') - these may differ from the values in K. 00148 # For monocular cameras, Tx = Ty = 0. Normally, monocular cameras will 00149 # also have R = the identity and P[1:3,1:3] = K. 00150 # For a stereo pair, the fourth column [Tx Ty 0]' is related to the 00151 # position of the optical center of the second camera in the first 00152 # camera's frame. We assume Tz = 0 so both cameras are in the same 00153 # stereo image plane. The first camera always has Tx = Ty = 0. For 00154 # the right (second) camera of a horizontal stereo pair, Ty = 0 and 00155 # Tx = -fx' * B, where B is the baseline between the cameras. 00156 # Given a 3D point [X Y Z]', the projection (x, y) of the point onto 00157 # the rectified image is given by: 00158 # [u v w]' = P * [X Y Z 1]' 00159 # x = u / w 00160 # y = v / w 00161 # This holds for both images of a stereo pair. 00162 float64[12] P # 3x4 row-major matrix 00163 00164 00165 ####################################################################### 00166 # Operational Parameters # 00167 ####################################################################### 00168 # These define the image region actually captured by the camera # 00169 # driver. Although they affect the geometry of the output image, they # 00170 # may be changed freely without recalibrating the camera. # 00171 ####################################################################### 00172 00173 # Binning refers here to any camera setting which combines rectangular 00174 # neighborhoods of pixels into larger "super-pixels." It reduces the 00175 # resolution of the output image to 00176 # (width / binning_x) x (height / binning_y). 00177 # The default values binning_x = binning_y = 0 is considered the same 00178 # as binning_x = binning_y = 1 (no subsampling). 00179 uint32 binning_x 00180 uint32 binning_y 00181 00182 # Region of interest (subwindow of full camera resolution), given in 00183 # full resolution (unbinned) image coordinates. A particular ROI 00184 # always denotes the same window of pixels on the camera sensor, 00185 # regardless of binning settings. 00186 # The default setting of roi (all values 0) is considered the same as 00187 # full resolution (roi.width = width, roi.height = height). 00188 RegionOfInterest roi 00189 00190 ================================================================================ 00191 MSG: sensor_msgs/RegionOfInterest 00192 # This message is used to specify a region of interest within an image. 00193 # 00194 # When used to specify the ROI setting of the camera when the image was 00195 # taken, the height and width fields should either match the height and 00196 # width fields for the associated image; or height = width = 0 00197 # indicates that the full resolution image was captured. 00198 00199 uint32 x_offset # Leftmost pixel of the ROI 00200 # (0 if the ROI includes the left edge of the image) 00201 uint32 y_offset # Topmost pixel of the ROI 00202 # (0 if the ROI includes the top edge of the image) 00203 uint32 height # Height of ROI 00204 uint32 width # Width of ROI 00205 00206 # True if a distinct rectified ROI should be calculated from the "raw" 00207 # ROI in this message. Typically this should be False if the full image 00208 # is captured (ROI not used), and True if a subwindow is captured (ROI 00209 # used). 00210 bool do_rectify 00211 00212 ================================================================================ 00213 MSG: worldmodel_msgs/PerceptInfo 00214 # This message contains information about the estimated class and object identity 00215 00216 # A string identifying the object's class (all objects of a class look the same) 00217 string class_id 00218 00219 # The class association support of the observation 00220 # The support is the log odd likelihood ratio given by log(p(y/observation y belongs to object of class class_id) / p(y/observation y is a false positive)) 00221 float32 class_support 00222 00223 # A string identifying a specific object 00224 string object_id 00225 00226 # The object association support of the observation 00227 # The support is the log odd likelihood ratio given by log(p(observation belongs to object object_id) / p(observation is false positive or belongs to another object)) 00228 float32 object_support 00229 00230 # A string that contains the name or a description of the specific object 00231 string name 00232 00233 """ 00234 __slots__ = ['header','camera_info','x','y','width','height','distance','info'] 00235 _slot_types = ['Header','sensor_msgs/CameraInfo','float32','float32','float32','float32','float32','worldmodel_msgs/PerceptInfo'] 00236 00237 def __init__(self, *args, **kwds): 00238 """ 00239 Constructor. Any message fields that are implicitly/explicitly 00240 set to None will be assigned a default value. The recommend 00241 use is keyword arguments as this is more robust to future message 00242 changes. You cannot mix in-order arguments and keyword arguments. 00243 00244 The available fields are: 00245 header,camera_info,x,y,width,height,distance,info 00246 00247 @param args: complete set of field values, in .msg order 00248 @param kwds: use keyword arguments corresponding to message field names 00249 to set specific fields. 00250 """ 00251 if args or kwds: 00252 super(ImagePercept, self).__init__(*args, **kwds) 00253 #message fields cannot be None, assign default values for those that are 00254 if self.header is None: 00255 self.header = std_msgs.msg._Header.Header() 00256 if self.camera_info is None: 00257 self.camera_info = sensor_msgs.msg.CameraInfo() 00258 if self.x is None: 00259 self.x = 0. 00260 if self.y is None: 00261 self.y = 0. 00262 if self.width is None: 00263 self.width = 0. 00264 if self.height is None: 00265 self.height = 0. 00266 if self.distance is None: 00267 self.distance = 0. 00268 if self.info is None: 00269 self.info = worldmodel_msgs.msg.PerceptInfo() 00270 else: 00271 self.header = std_msgs.msg._Header.Header() 00272 self.camera_info = sensor_msgs.msg.CameraInfo() 00273 self.x = 0. 00274 self.y = 0. 00275 self.width = 0. 00276 self.height = 0. 00277 self.distance = 0. 00278 self.info = worldmodel_msgs.msg.PerceptInfo() 00279 00280 def _get_types(self): 00281 """ 00282 internal API method 00283 """ 00284 return self._slot_types 00285 00286 def serialize(self, buff): 00287 """ 00288 serialize message into buffer 00289 @param buff: buffer 00290 @type buff: StringIO 00291 """ 00292 try: 00293 _x = self 00294 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00295 _x = self.header.frame_id 00296 length = len(_x) 00297 buff.write(struct.pack('<I%ss'%length, length, _x)) 00298 _x = self 00299 buff.write(_struct_3I.pack(_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs)) 00300 _x = self.camera_info.header.frame_id 00301 length = len(_x) 00302 buff.write(struct.pack('<I%ss'%length, length, _x)) 00303 _x = self 00304 buff.write(_struct_2I.pack(_x.camera_info.height, _x.camera_info.width)) 00305 _x = self.camera_info.distortion_model 00306 length = len(_x) 00307 buff.write(struct.pack('<I%ss'%length, length, _x)) 00308 length = len(self.camera_info.D) 00309 buff.write(_struct_I.pack(length)) 00310 pattern = '<%sd'%length 00311 buff.write(struct.pack(pattern, *self.camera_info.D)) 00312 buff.write(_struct_9d.pack(*self.camera_info.K)) 00313 buff.write(_struct_9d.pack(*self.camera_info.R)) 00314 buff.write(_struct_12d.pack(*self.camera_info.P)) 00315 _x = self 00316 buff.write(_struct_6IB5f.pack(_x.camera_info.binning_x, _x.camera_info.binning_y, _x.camera_info.roi.x_offset, _x.camera_info.roi.y_offset, _x.camera_info.roi.height, _x.camera_info.roi.width, _x.camera_info.roi.do_rectify, _x.x, _x.y, _x.width, _x.height, _x.distance)) 00317 _x = self.info.class_id 00318 length = len(_x) 00319 buff.write(struct.pack('<I%ss'%length, length, _x)) 00320 buff.write(_struct_f.pack(self.info.class_support)) 00321 _x = self.info.object_id 00322 length = len(_x) 00323 buff.write(struct.pack('<I%ss'%length, length, _x)) 00324 buff.write(_struct_f.pack(self.info.object_support)) 00325 _x = self.info.name 00326 length = len(_x) 00327 buff.write(struct.pack('<I%ss'%length, length, _x)) 00328 except struct.error as se: self._check_types(se) 00329 except TypeError as te: self._check_types(te) 00330 00331 def deserialize(self, str): 00332 """ 00333 unpack serialized message in str into this message instance 00334 @param str: byte array of serialized message 00335 @type str: str 00336 """ 00337 try: 00338 if self.header is None: 00339 self.header = std_msgs.msg._Header.Header() 00340 if self.camera_info is None: 00341 self.camera_info = sensor_msgs.msg.CameraInfo() 00342 if self.info is None: 00343 self.info = worldmodel_msgs.msg.PerceptInfo() 00344 end = 0 00345 _x = self 00346 start = end 00347 end += 12 00348 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00349 start = end 00350 end += 4 00351 (length,) = _struct_I.unpack(str[start:end]) 00352 start = end 00353 end += length 00354 self.header.frame_id = str[start:end] 00355 _x = self 00356 start = end 00357 end += 12 00358 (_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00359 start = end 00360 end += 4 00361 (length,) = _struct_I.unpack(str[start:end]) 00362 start = end 00363 end += length 00364 self.camera_info.header.frame_id = str[start:end] 00365 _x = self 00366 start = end 00367 end += 8 00368 (_x.camera_info.height, _x.camera_info.width,) = _struct_2I.unpack(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.camera_info.distortion_model = str[start:end] 00375 start = end 00376 end += 4 00377 (length,) = _struct_I.unpack(str[start:end]) 00378 pattern = '<%sd'%length 00379 start = end 00380 end += struct.calcsize(pattern) 00381 self.camera_info.D = struct.unpack(pattern, str[start:end]) 00382 start = end 00383 end += 72 00384 self.camera_info.K = _struct_9d.unpack(str[start:end]) 00385 start = end 00386 end += 72 00387 self.camera_info.R = _struct_9d.unpack(str[start:end]) 00388 start = end 00389 end += 96 00390 self.camera_info.P = _struct_12d.unpack(str[start:end]) 00391 _x = self 00392 start = end 00393 end += 45 00394 (_x.camera_info.binning_x, _x.camera_info.binning_y, _x.camera_info.roi.x_offset, _x.camera_info.roi.y_offset, _x.camera_info.roi.height, _x.camera_info.roi.width, _x.camera_info.roi.do_rectify, _x.x, _x.y, _x.width, _x.height, _x.distance,) = _struct_6IB5f.unpack(str[start:end]) 00395 self.camera_info.roi.do_rectify = bool(self.camera_info.roi.do_rectify) 00396 start = end 00397 end += 4 00398 (length,) = _struct_I.unpack(str[start:end]) 00399 start = end 00400 end += length 00401 self.info.class_id = str[start:end] 00402 start = end 00403 end += 4 00404 (self.info.class_support,) = _struct_f.unpack(str[start:end]) 00405 start = end 00406 end += 4 00407 (length,) = _struct_I.unpack(str[start:end]) 00408 start = end 00409 end += length 00410 self.info.object_id = str[start:end] 00411 start = end 00412 end += 4 00413 (self.info.object_support,) = _struct_f.unpack(str[start:end]) 00414 start = end 00415 end += 4 00416 (length,) = _struct_I.unpack(str[start:end]) 00417 start = end 00418 end += length 00419 self.info.name = str[start:end] 00420 return self 00421 except struct.error as e: 00422 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00423 00424 00425 def serialize_numpy(self, buff, numpy): 00426 """ 00427 serialize message with numpy array types into buffer 00428 @param buff: buffer 00429 @type buff: StringIO 00430 @param numpy: numpy python module 00431 @type numpy module 00432 """ 00433 try: 00434 _x = self 00435 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00436 _x = self.header.frame_id 00437 length = len(_x) 00438 buff.write(struct.pack('<I%ss'%length, length, _x)) 00439 _x = self 00440 buff.write(_struct_3I.pack(_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs)) 00441 _x = self.camera_info.header.frame_id 00442 length = len(_x) 00443 buff.write(struct.pack('<I%ss'%length, length, _x)) 00444 _x = self 00445 buff.write(_struct_2I.pack(_x.camera_info.height, _x.camera_info.width)) 00446 _x = self.camera_info.distortion_model 00447 length = len(_x) 00448 buff.write(struct.pack('<I%ss'%length, length, _x)) 00449 length = len(self.camera_info.D) 00450 buff.write(_struct_I.pack(length)) 00451 pattern = '<%sd'%length 00452 buff.write(self.camera_info.D.tostring()) 00453 buff.write(self.camera_info.K.tostring()) 00454 buff.write(self.camera_info.R.tostring()) 00455 buff.write(self.camera_info.P.tostring()) 00456 _x = self 00457 buff.write(_struct_6IB5f.pack(_x.camera_info.binning_x, _x.camera_info.binning_y, _x.camera_info.roi.x_offset, _x.camera_info.roi.y_offset, _x.camera_info.roi.height, _x.camera_info.roi.width, _x.camera_info.roi.do_rectify, _x.x, _x.y, _x.width, _x.height, _x.distance)) 00458 _x = self.info.class_id 00459 length = len(_x) 00460 buff.write(struct.pack('<I%ss'%length, length, _x)) 00461 buff.write(_struct_f.pack(self.info.class_support)) 00462 _x = self.info.object_id 00463 length = len(_x) 00464 buff.write(struct.pack('<I%ss'%length, length, _x)) 00465 buff.write(_struct_f.pack(self.info.object_support)) 00466 _x = self.info.name 00467 length = len(_x) 00468 buff.write(struct.pack('<I%ss'%length, length, _x)) 00469 except struct.error as se: self._check_types(se) 00470 except TypeError as te: self._check_types(te) 00471 00472 def deserialize_numpy(self, str, numpy): 00473 """ 00474 unpack serialized message in str into this message instance using numpy for array types 00475 @param str: byte array of serialized message 00476 @type str: str 00477 @param numpy: numpy python module 00478 @type numpy: module 00479 """ 00480 try: 00481 if self.header is None: 00482 self.header = std_msgs.msg._Header.Header() 00483 if self.camera_info is None: 00484 self.camera_info = sensor_msgs.msg.CameraInfo() 00485 if self.info is None: 00486 self.info = worldmodel_msgs.msg.PerceptInfo() 00487 end = 0 00488 _x = self 00489 start = end 00490 end += 12 00491 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00492 start = end 00493 end += 4 00494 (length,) = _struct_I.unpack(str[start:end]) 00495 start = end 00496 end += length 00497 self.header.frame_id = str[start:end] 00498 _x = self 00499 start = end 00500 end += 12 00501 (_x.camera_info.header.seq, _x.camera_info.header.stamp.secs, _x.camera_info.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00502 start = end 00503 end += 4 00504 (length,) = _struct_I.unpack(str[start:end]) 00505 start = end 00506 end += length 00507 self.camera_info.header.frame_id = str[start:end] 00508 _x = self 00509 start = end 00510 end += 8 00511 (_x.camera_info.height, _x.camera_info.width,) = _struct_2I.unpack(str[start:end]) 00512 start = end 00513 end += 4 00514 (length,) = _struct_I.unpack(str[start:end]) 00515 start = end 00516 end += length 00517 self.camera_info.distortion_model = str[start:end] 00518 start = end 00519 end += 4 00520 (length,) = _struct_I.unpack(str[start:end]) 00521 pattern = '<%sd'%length 00522 start = end 00523 end += struct.calcsize(pattern) 00524 self.camera_info.D = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=length) 00525 start = end 00526 end += 72 00527 self.camera_info.K = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9) 00528 start = end 00529 end += 72 00530 self.camera_info.R = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=9) 00531 start = end 00532 end += 96 00533 self.camera_info.P = numpy.frombuffer(str[start:end], dtype=numpy.float64, count=12) 00534 _x = self 00535 start = end 00536 end += 45 00537 (_x.camera_info.binning_x, _x.camera_info.binning_y, _x.camera_info.roi.x_offset, _x.camera_info.roi.y_offset, _x.camera_info.roi.height, _x.camera_info.roi.width, _x.camera_info.roi.do_rectify, _x.x, _x.y, _x.width, _x.height, _x.distance,) = _struct_6IB5f.unpack(str[start:end]) 00538 self.camera_info.roi.do_rectify = bool(self.camera_info.roi.do_rectify) 00539 start = end 00540 end += 4 00541 (length,) = _struct_I.unpack(str[start:end]) 00542 start = end 00543 end += length 00544 self.info.class_id = str[start:end] 00545 start = end 00546 end += 4 00547 (self.info.class_support,) = _struct_f.unpack(str[start:end]) 00548 start = end 00549 end += 4 00550 (length,) = _struct_I.unpack(str[start:end]) 00551 start = end 00552 end += length 00553 self.info.object_id = str[start:end] 00554 start = end 00555 end += 4 00556 (self.info.object_support,) = _struct_f.unpack(str[start:end]) 00557 start = end 00558 end += 4 00559 (length,) = _struct_I.unpack(str[start:end]) 00560 start = end 00561 end += length 00562 self.info.name = str[start:end] 00563 return self 00564 except struct.error as e: 00565 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00566 00567 _struct_I = roslib.message.struct_I 00568 _struct_12d = struct.Struct("<12d") 00569 _struct_f = struct.Struct("<f") 00570 _struct_9d = struct.Struct("<9d") 00571 _struct_3I = struct.Struct("<3I") 00572 _struct_6IB5f = struct.Struct("<6IB5f") 00573 _struct_2I = struct.Struct("<2I")