$search
00001 """autogenerated by genmsg_py from DisparityImage.msg. Do not edit.""" 00002 import roslib.message 00003 import struct 00004 00005 import sensor_msgs.msg 00006 import std_msgs.msg 00007 00008 class DisparityImage(roslib.message.Message): 00009 _md5sum = "04a177815f75271039fa21f16acad8c9" 00010 _type = "stereo_msgs/DisparityImage" 00011 _has_header = True #flag to mark the presence of a Header object 00012 _full_text = """# Separate header for compatibility with current TimeSynchronizer. 00013 # Likely to be removed in a later release, use image.header instead. 00014 Header header 00015 00016 # Floating point disparity image. The disparities are pre-adjusted for any 00017 # x-offset between the principal points of the two cameras (in the case 00018 # that they are verged). That is: d = x_l - x_r - (cx_l - cx_r) 00019 sensor_msgs/Image image 00020 00021 # Stereo geometry. For disparity d, the depth from the camera is Z = fT/d. 00022 float32 f # Focal length, pixels 00023 float32 T # Baseline, world units 00024 00025 # Subwindow of (potentially) valid disparity values. 00026 sensor_msgs/RegionOfInterest valid_window 00027 00028 # The range of disparities searched. 00029 # In the disparity image, any disparity less than min_disparity is invalid. 00030 # The disparity search range defines the horopter, or 3D volume that the 00031 # stereo algorithm can "see". Points with Z outside of: 00032 # Z_min = fT / max_disparity 00033 # Z_max = fT / min_disparity 00034 # could not be found. 00035 float32 min_disparity 00036 float32 max_disparity 00037 00038 # Smallest allowed disparity increment. The smallest achievable depth range 00039 # resolution is delta_Z = (Z^2/fT)*delta_d. 00040 float32 delta_d 00041 00042 ================================================================================ 00043 MSG: std_msgs/Header 00044 # Standard metadata for higher-level stamped data types. 00045 # This is generally used to communicate timestamped data 00046 # in a particular coordinate frame. 00047 # 00048 # sequence ID: consecutively increasing ID 00049 uint32 seq 00050 #Two-integer timestamp that is expressed as: 00051 # * stamp.secs: seconds (stamp_secs) since epoch 00052 # * stamp.nsecs: nanoseconds since stamp_secs 00053 # time-handling sugar is provided by the client library 00054 time stamp 00055 #Frame this data is associated with 00056 # 0: no frame 00057 # 1: global frame 00058 string frame_id 00059 00060 ================================================================================ 00061 MSG: sensor_msgs/Image 00062 # This message contains an uncompressed image 00063 # (0, 0) is at top-left corner of image 00064 # 00065 00066 Header header # Header timestamp should be acquisition time of image 00067 # Header frame_id should be optical frame of camera 00068 # origin of frame should be optical center of cameara 00069 # +x should point to the right in the image 00070 # +y should point down in the image 00071 # +z should point into to plane of the image 00072 # If the frame_id here and the frame_id of the CameraInfo 00073 # message associated with the image conflict 00074 # the behavior is undefined 00075 00076 uint32 height # image height, that is, number of rows 00077 uint32 width # image width, that is, number of columns 00078 00079 # The legal values for encoding are in file src/image_encodings.cpp 00080 # If you want to standardize a new string format, join 00081 # ros-users@lists.sourceforge.net and send an email proposing a new encoding. 00082 00083 string encoding # Encoding of pixels -- channel meaning, ordering, size 00084 # taken from the list of strings in src/image_encodings.cpp 00085 00086 uint8 is_bigendian # is this data bigendian? 00087 uint32 step # Full row length in bytes 00088 uint8[] data # actual matrix data, size is (step * rows) 00089 00090 ================================================================================ 00091 MSG: sensor_msgs/RegionOfInterest 00092 # This message is used to specify a region of interest within an image. 00093 # 00094 # When used to specify the ROI setting of the camera when the image was 00095 # taken, the height and width fields should either match the height and 00096 # width fields for the associated image; or height = width = 0 00097 # indicates that the full resolution image was captured. 00098 00099 uint32 x_offset # Leftmost pixel of the ROI 00100 # (0 if the ROI includes the left edge of the image) 00101 uint32 y_offset # Topmost pixel of the ROI 00102 # (0 if the ROI includes the top edge of the image) 00103 uint32 height # Height of ROI 00104 uint32 width # Width of ROI 00105 00106 # True if a distinct rectified ROI should be calculated from the "raw" 00107 # ROI in this message. Typically this should be False if the full image 00108 # is captured (ROI not used), and True if a subwindow is captured (ROI 00109 # used). 00110 bool do_rectify 00111 00112 """ 00113 __slots__ = ['header','image','f','T','valid_window','min_disparity','max_disparity','delta_d'] 00114 _slot_types = ['Header','sensor_msgs/Image','float32','float32','sensor_msgs/RegionOfInterest','float32','float32','float32'] 00115 00116 def __init__(self, *args, **kwds): 00117 """ 00118 Constructor. Any message fields that are implicitly/explicitly 00119 set to None will be assigned a default value. The recommend 00120 use is keyword arguments as this is more robust to future message 00121 changes. You cannot mix in-order arguments and keyword arguments. 00122 00123 The available fields are: 00124 header,image,f,T,valid_window,min_disparity,max_disparity,delta_d 00125 00126 @param args: complete set of field values, in .msg order 00127 @param kwds: use keyword arguments corresponding to message field names 00128 to set specific fields. 00129 """ 00130 if args or kwds: 00131 super(DisparityImage, self).__init__(*args, **kwds) 00132 #message fields cannot be None, assign default values for those that are 00133 if self.header is None: 00134 self.header = std_msgs.msg._Header.Header() 00135 if self.image is None: 00136 self.image = sensor_msgs.msg.Image() 00137 if self.f is None: 00138 self.f = 0. 00139 if self.T is None: 00140 self.T = 0. 00141 if self.valid_window is None: 00142 self.valid_window = sensor_msgs.msg.RegionOfInterest() 00143 if self.min_disparity is None: 00144 self.min_disparity = 0. 00145 if self.max_disparity is None: 00146 self.max_disparity = 0. 00147 if self.delta_d is None: 00148 self.delta_d = 0. 00149 else: 00150 self.header = std_msgs.msg._Header.Header() 00151 self.image = sensor_msgs.msg.Image() 00152 self.f = 0. 00153 self.T = 0. 00154 self.valid_window = sensor_msgs.msg.RegionOfInterest() 00155 self.min_disparity = 0. 00156 self.max_disparity = 0. 00157 self.delta_d = 0. 00158 00159 def _get_types(self): 00160 """ 00161 internal API method 00162 """ 00163 return self._slot_types 00164 00165 def serialize(self, buff): 00166 """ 00167 serialize message into buffer 00168 @param buff: buffer 00169 @type buff: StringIO 00170 """ 00171 try: 00172 _x = self 00173 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00174 _x = self.header.frame_id 00175 length = len(_x) 00176 buff.write(struct.pack('<I%ss'%length, length, _x)) 00177 _x = self 00178 buff.write(_struct_3I.pack(_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs)) 00179 _x = self.image.header.frame_id 00180 length = len(_x) 00181 buff.write(struct.pack('<I%ss'%length, length, _x)) 00182 _x = self 00183 buff.write(_struct_2I.pack(_x.image.height, _x.image.width)) 00184 _x = self.image.encoding 00185 length = len(_x) 00186 buff.write(struct.pack('<I%ss'%length, length, _x)) 00187 _x = self 00188 buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step)) 00189 _x = self.image.data 00190 length = len(_x) 00191 # - if encoded as a list instead, serialize as bytes instead of string 00192 if type(_x) in [list, tuple]: 00193 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00194 else: 00195 buff.write(struct.pack('<I%ss'%length, length, _x)) 00196 _x = self 00197 buff.write(_struct_2f4IB3f.pack(_x.f, _x.T, _x.valid_window.x_offset, _x.valid_window.y_offset, _x.valid_window.height, _x.valid_window.width, _x.valid_window.do_rectify, _x.min_disparity, _x.max_disparity, _x.delta_d)) 00198 except struct.error as se: self._check_types(se) 00199 except TypeError as te: self._check_types(te) 00200 00201 def deserialize(self, str): 00202 """ 00203 unpack serialized message in str into this message instance 00204 @param str: byte array of serialized message 00205 @type str: str 00206 """ 00207 try: 00208 if self.header is None: 00209 self.header = std_msgs.msg._Header.Header() 00210 if self.image is None: 00211 self.image = sensor_msgs.msg.Image() 00212 if self.valid_window is None: 00213 self.valid_window = sensor_msgs.msg.RegionOfInterest() 00214 end = 0 00215 _x = self 00216 start = end 00217 end += 12 00218 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00219 start = end 00220 end += 4 00221 (length,) = _struct_I.unpack(str[start:end]) 00222 start = end 00223 end += length 00224 self.header.frame_id = str[start:end] 00225 _x = self 00226 start = end 00227 end += 12 00228 (_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00229 start = end 00230 end += 4 00231 (length,) = _struct_I.unpack(str[start:end]) 00232 start = end 00233 end += length 00234 self.image.header.frame_id = str[start:end] 00235 _x = self 00236 start = end 00237 end += 8 00238 (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end]) 00239 start = end 00240 end += 4 00241 (length,) = _struct_I.unpack(str[start:end]) 00242 start = end 00243 end += length 00244 self.image.encoding = str[start:end] 00245 _x = self 00246 start = end 00247 end += 5 00248 (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end]) 00249 start = end 00250 end += 4 00251 (length,) = _struct_I.unpack(str[start:end]) 00252 start = end 00253 end += length 00254 self.image.data = str[start:end] 00255 _x = self 00256 start = end 00257 end += 37 00258 (_x.f, _x.T, _x.valid_window.x_offset, _x.valid_window.y_offset, _x.valid_window.height, _x.valid_window.width, _x.valid_window.do_rectify, _x.min_disparity, _x.max_disparity, _x.delta_d,) = _struct_2f4IB3f.unpack(str[start:end]) 00259 self.valid_window.do_rectify = bool(self.valid_window.do_rectify) 00260 return self 00261 except struct.error as e: 00262 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00263 00264 00265 def serialize_numpy(self, buff, numpy): 00266 """ 00267 serialize message with numpy array types into buffer 00268 @param buff: buffer 00269 @type buff: StringIO 00270 @param numpy: numpy python module 00271 @type numpy module 00272 """ 00273 try: 00274 _x = self 00275 buff.write(_struct_3I.pack(_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs)) 00276 _x = self.header.frame_id 00277 length = len(_x) 00278 buff.write(struct.pack('<I%ss'%length, length, _x)) 00279 _x = self 00280 buff.write(_struct_3I.pack(_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs)) 00281 _x = self.image.header.frame_id 00282 length = len(_x) 00283 buff.write(struct.pack('<I%ss'%length, length, _x)) 00284 _x = self 00285 buff.write(_struct_2I.pack(_x.image.height, _x.image.width)) 00286 _x = self.image.encoding 00287 length = len(_x) 00288 buff.write(struct.pack('<I%ss'%length, length, _x)) 00289 _x = self 00290 buff.write(_struct_BI.pack(_x.image.is_bigendian, _x.image.step)) 00291 _x = self.image.data 00292 length = len(_x) 00293 # - if encoded as a list instead, serialize as bytes instead of string 00294 if type(_x) in [list, tuple]: 00295 buff.write(struct.pack('<I%sB'%length, length, *_x)) 00296 else: 00297 buff.write(struct.pack('<I%ss'%length, length, _x)) 00298 _x = self 00299 buff.write(_struct_2f4IB3f.pack(_x.f, _x.T, _x.valid_window.x_offset, _x.valid_window.y_offset, _x.valid_window.height, _x.valid_window.width, _x.valid_window.do_rectify, _x.min_disparity, _x.max_disparity, _x.delta_d)) 00300 except struct.error as se: self._check_types(se) 00301 except TypeError as te: self._check_types(te) 00302 00303 def deserialize_numpy(self, str, numpy): 00304 """ 00305 unpack serialized message in str into this message instance using numpy for array types 00306 @param str: byte array of serialized message 00307 @type str: str 00308 @param numpy: numpy python module 00309 @type numpy: module 00310 """ 00311 try: 00312 if self.header is None: 00313 self.header = std_msgs.msg._Header.Header() 00314 if self.image is None: 00315 self.image = sensor_msgs.msg.Image() 00316 if self.valid_window is None: 00317 self.valid_window = sensor_msgs.msg.RegionOfInterest() 00318 end = 0 00319 _x = self 00320 start = end 00321 end += 12 00322 (_x.header.seq, _x.header.stamp.secs, _x.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00323 start = end 00324 end += 4 00325 (length,) = _struct_I.unpack(str[start:end]) 00326 start = end 00327 end += length 00328 self.header.frame_id = str[start:end] 00329 _x = self 00330 start = end 00331 end += 12 00332 (_x.image.header.seq, _x.image.header.stamp.secs, _x.image.header.stamp.nsecs,) = _struct_3I.unpack(str[start:end]) 00333 start = end 00334 end += 4 00335 (length,) = _struct_I.unpack(str[start:end]) 00336 start = end 00337 end += length 00338 self.image.header.frame_id = str[start:end] 00339 _x = self 00340 start = end 00341 end += 8 00342 (_x.image.height, _x.image.width,) = _struct_2I.unpack(str[start:end]) 00343 start = end 00344 end += 4 00345 (length,) = _struct_I.unpack(str[start:end]) 00346 start = end 00347 end += length 00348 self.image.encoding = str[start:end] 00349 _x = self 00350 start = end 00351 end += 5 00352 (_x.image.is_bigendian, _x.image.step,) = _struct_BI.unpack(str[start:end]) 00353 start = end 00354 end += 4 00355 (length,) = _struct_I.unpack(str[start:end]) 00356 start = end 00357 end += length 00358 self.image.data = str[start:end] 00359 _x = self 00360 start = end 00361 end += 37 00362 (_x.f, _x.T, _x.valid_window.x_offset, _x.valid_window.y_offset, _x.valid_window.height, _x.valid_window.width, _x.valid_window.do_rectify, _x.min_disparity, _x.max_disparity, _x.delta_d,) = _struct_2f4IB3f.unpack(str[start:end]) 00363 self.valid_window.do_rectify = bool(self.valid_window.do_rectify) 00364 return self 00365 except struct.error as e: 00366 raise roslib.message.DeserializationError(e) #most likely buffer underfill 00367 00368 _struct_I = roslib.message.struct_I 00369 _struct_2f4IB3f = struct.Struct("<2f4IB3f") 00370 _struct_3I = struct.Struct("<3I") 00371 _struct_2I = struct.Struct("<2I") 00372 _struct_BI = struct.Struct("<BI")