ZED Open Capture  v0.6.0
Low level camera driver for the ZED stereo camera family
Functions
zed_oc_depth_example.cpp File Reference

Go to the source code of this file.

Functions

int main (int argc, char *argv[])
 

Function Documentation

◆ main()

int main ( int  argc,
char *  argv[] 
)
Examples
zed_oc_depth_example.cpp.

Definition at line 48 of file zed_oc_depth_example.cpp.

49 {
50  // ----> Silence unused warning
51  (void)argc;
52  (void)argv;
53  // <---- Silence unused warning
54 
56 
57  // ----> Set Video parameters
59 #ifdef EMBEDDED_ARM
61 #else
63 #endif
65  params.verbose = verbose;
66  // <---- Set Video parameters
67 
68  // ----> Create Video Capture
70  if( !cap.initializeVideo(-1) )
71  {
72  std::cerr << "Cannot open camera video capture" << std::endl;
73  std::cerr << "See verbosity level for more details." << std::endl;
74 
75  return EXIT_FAILURE;
76  }
77  int sn = cap.getSerialNumber();
78  std::cout << "Connected to camera sn: " << sn << std::endl;
79  // <---- Create Video Capture
80 
81  // ----> Retrieve calibration file from Stereolabs server
82  std::string calibration_file;
83  // ZED Calibration
84  unsigned int serial_number = sn;
85  // Download camera calibration file
86  if( !sl_oc::tools::downloadCalibrationFile(serial_number, calibration_file) )
87  {
88  std::cerr << "Could not load calibration file from Stereolabs servers" << std::endl;
89  return EXIT_FAILURE;
90  }
91  std::cout << "Calibration file found. Loading..." << std::endl;
92 
93  // ----> Frame size
94  int w,h;
95  cap.getFrameSize(w,h);
96  // <---- Frame size
97 
98  // ----> Initialize calibration
99  cv::Mat map_left_x, map_left_y;
100  cv::Mat map_right_x, map_right_y;
101  cv::Mat cameraMatrix_left, cameraMatrix_right;
102  double baseline=0;
103  sl_oc::tools::initCalibration(calibration_file, cv::Size(w/2,h), map_left_x, map_left_y, map_right_x, map_right_y,
104  cameraMatrix_left, cameraMatrix_right, &baseline);
105 
106  double fx = cameraMatrix_left.at<double>(0,0);
107  double fy = cameraMatrix_left.at<double>(1,1);
108  double cx = cameraMatrix_left.at<double>(0,2);
109  double cy = cameraMatrix_left.at<double>(1,2);
110 
111  std::cout << " Camera Matrix L: \n" << cameraMatrix_left << std::endl << std::endl;
112  std::cout << " Camera Matrix R: \n" << cameraMatrix_right << std::endl << std::endl;
113 
114 #ifdef USE_OCV_TAPI
115  cv::UMat map_left_x_gpu = map_left_x.getUMat(cv::ACCESS_READ,cv::USAGE_ALLOCATE_DEVICE_MEMORY);
116  cv::UMat map_left_y_gpu = map_left_y.getUMat(cv::ACCESS_READ,cv::USAGE_ALLOCATE_DEVICE_MEMORY);
117  cv::UMat map_right_x_gpu = map_right_x.getUMat(cv::ACCESS_READ,cv::USAGE_ALLOCATE_DEVICE_MEMORY);
118  cv::UMat map_right_y_gpu = map_right_y.getUMat(cv::ACCESS_READ,cv::USAGE_ALLOCATE_DEVICE_MEMORY);
119 #endif
120  // ----> Initialize calibration
121 
122  // ----> Declare OpenCV images
123 #ifdef USE_OCV_TAPI
124  cv::UMat frameYUV; // Full frame side-by-side in YUV 4:2:2 format
125  cv::UMat frameBGR(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Full frame side-by-side in BGR format
126  cv::UMat left_raw(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Left unrectified image
127  cv::UMat right_raw(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Right unrectified image
128  cv::UMat left_rect(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Left rectified image
129  cv::UMat right_rect(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Right rectified image
130  cv::UMat left_for_matcher(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Left image for the stereo matcher
131  cv::UMat right_for_matcher(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Right image for the stereo matcher
132  cv::UMat left_disp_half(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Half sized disparity map
133  cv::UMat left_disp(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Full output disparity
134  cv::UMat left_disp_float(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Final disparity map in float32
135  cv::UMat left_disp_image(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Normalized and color remapped disparity map to be displayed
136  cv::UMat left_depth_map(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Depth map in float32
137 #else
139 #endif
140  // <---- Declare OpenCV images
141 
142  // ----> Stereo matcher initialization
144 
145  //Note: you can use the tool 'zed_open_capture_depth_tune_stereo' to tune the parameters and save them to YAML
146  if(!stereoPar.load())
147  {
148  stereoPar.save(); // Save default parameters.
149  }
150 
151  cv::Ptr<cv::StereoSGBM> left_matcher = cv::StereoSGBM::create(stereoPar.minDisparity,stereoPar.numDisparities,stereoPar.blockSize);
152  left_matcher->setMinDisparity(stereoPar.minDisparity);
153  left_matcher->setNumDisparities(stereoPar.numDisparities);
154  left_matcher->setBlockSize(stereoPar.blockSize);
155  left_matcher->setP1(stereoPar.P1);
156  left_matcher->setP2(stereoPar.P2);
157  left_matcher->setDisp12MaxDiff(stereoPar.disp12MaxDiff);
158  left_matcher->setMode(stereoPar.mode);
159  left_matcher->setPreFilterCap(stereoPar.preFilterCap);
160  left_matcher->setUniquenessRatio(stereoPar.uniquenessRatio);
161  left_matcher->setSpeckleWindowSize(stereoPar.speckleWindowSize);
162  left_matcher->setSpeckleRange(stereoPar.speckleRange);
163 
164  stereoPar.print();
165  // <---- Stereo matcher initialization
166 
167 
168  // ----> Point Cloud
169  cv::Mat cloudMat;
170 
171 #ifdef HAVE_OPENCV_VIZ
172  cv::viz::Viz3d pc_viewer = cv::viz::Viz3d( "Point Cloud" );
173 #endif
174  // <---- Point Cloud
175 
176 
177  uint64_t last_ts=0; // Used to check new frame arrival
178 
179  // Infinite video grabbing loop
180  while (1)
181  {
182  // Get a new frame from camera
183  const sl_oc::video::Frame frame = cap.getLastFrame();
184 
185  // ----> If the frame is valid we can convert, rectify and display it
186  if(frame.data!=nullptr && frame.timestamp!=last_ts)
187  {
188  last_ts = frame.timestamp;
189 
190  // ----> Conversion from YUV 4:2:2 to BGR for visualization
191 #ifdef USE_OCV_TAPI
192  cv::Mat frameYUV_cpu = cv::Mat( frame.height, frame.width, CV_8UC2, frame.data );
193  frameYUV = frameYUV_cpu.getUMat(cv::ACCESS_READ,cv::USAGE_ALLOCATE_HOST_MEMORY);
194 #else
195  frameYUV = cv::Mat( frame.height, frame.width, CV_8UC2, frame.data );
196 #endif
197  cv::cvtColor(frameYUV,frameBGR,cv::COLOR_YUV2BGR_YUYV);
198  // <---- Conversion from YUV 4:2:2 to BGR for visualization
199 
200  // ----> Extract left and right images from side-by-side
201  left_raw = frameBGR(cv::Rect(0, 0, frameBGR.cols / 2, frameBGR.rows));
202  right_raw = frameBGR(cv::Rect(frameBGR.cols / 2, 0, frameBGR.cols / 2, frameBGR.rows));
203  // <---- Extract left and right images from side-by-side
204 
205  // ----> Apply rectification
206  sl_oc::tools::StopWatch remap_clock;
207 #ifdef USE_OCV_TAPI
208  cv::remap(left_raw, left_rect, map_left_x_gpu, map_left_y_gpu, cv::INTER_AREA );
209  cv::remap(right_raw, right_rect, map_right_x_gpu, map_right_y_gpu, cv::INTER_AREA );
210 #else
211  cv::remap(left_raw, left_rect, map_left_x, map_left_y, cv::INTER_AREA );
212  cv::remap(right_raw, right_rect, map_right_x, map_right_y, cv::INTER_AREA );
213 #endif
214  double remap_elapsed = remap_clock.toc();
215  std::stringstream remapElabInfo;
216  remapElabInfo << "Rectif. processing: " << remap_elapsed << " sec - Freq: " << 1./remap_elapsed;
217  // <---- Apply rectification
218 
219  // ----> Stereo matching
220  sl_oc::tools::StopWatch stereo_clock;
221  double resize_fact = 1.0;
222 #ifdef USE_HALF_SIZE_DISP
223  resize_fact = 0.5;
224  // Resize the original images to improve performances
225  cv::resize(left_rect, left_for_matcher, cv::Size(), resize_fact, resize_fact, cv::INTER_AREA);
226  cv::resize(right_rect, right_for_matcher, cv::Size(), resize_fact, resize_fact, cv::INTER_AREA);
227 #else
228  left_for_matcher = left_rect; // No data copy
229  right_for_matcher = right_rect; // No data copy
230 #endif
231  // Apply stereo matching
232  left_matcher->compute(left_for_matcher, right_for_matcher,left_disp_half);
233 
234  left_disp_half.convertTo(left_disp_float,CV_32FC1);
235  cv::multiply(left_disp_float,1./16.,left_disp_float); // Last 4 bits of SGBM disparity are decimal
236 
237 #ifdef USE_HALF_SIZE_DISP
238  cv::multiply(left_disp_float,2.,left_disp_float); // Last 4 bits of SGBM disparity are decimal
239  cv::UMat tmp = left_disp_float; // Required for OpenCV 3.2
240  cv::resize(tmp, left_disp_float, cv::Size(), 1./resize_fact, 1./resize_fact, cv::INTER_AREA);
241 #else
242  left_disp = left_disp_float;
243 #endif
244 
245 
246  double elapsed = stereo_clock.toc();
247  std::stringstream stereoElabInfo;
248  stereoElabInfo << "Stereo processing: " << elapsed << " sec - Freq: " << 1./elapsed;
249  // <---- Stereo matching
250 
251  // ----> Show frames
252  sl_oc::tools::showImage("Right rect.", right_rect, params.res,true, remapElabInfo.str());
253  sl_oc::tools::showImage("Left rect.", left_rect, params.res,true, remapElabInfo.str());
254  // <---- Show frames
255 
256  // ----> Show disparity image
257  cv::add(left_disp_float,-static_cast<double>(stereoPar.minDisparity-1),left_disp_float); // Minimum disparity offset correction
258  cv::multiply(left_disp_float,1./stereoPar.numDisparities,left_disp_image,255., CV_8UC1 ); // Normalization and rescaling
259 
260  cv::applyColorMap(left_disp_image,left_disp_image,cv::COLORMAP_JET); // COLORMAP_INFERNO is better, but it's only available starting from OpenCV v4.1.0
261 
262  sl_oc::tools::showImage("Disparity", left_disp_image, params.res,true, stereoElabInfo.str());
263  // <---- Show disparity image
264 
265  // ----> Extract Depth map
266  // The DISPARITY MAP can be now transformed in DEPTH MAP using the formula
267  // depth = (f * B) / disparity
268  // where 'f' is the camera focal, 'B' is the camera baseline, 'disparity' is the pixel disparity
269 
270  double num = static_cast<double>(fx*baseline);
271  cv::divide(num,left_disp_float,left_depth_map);
272 
273  float central_depth = left_depth_map.getMat(cv::ACCESS_READ).at<float>(left_depth_map.rows/2, left_depth_map.cols/2 );
274  std::cout << "Depth of the central pixel: " << central_depth << " mm" << std::endl;
275  // <---- Extract Depth map
276 
277  // ----> Create Point Cloud
278  sl_oc::tools::StopWatch pc_clock;
279  size_t buf_size = static_cast<size_t>(left_depth_map.cols * left_depth_map.rows);
280  std::vector<cv::Vec3d> buffer( buf_size, cv::Vec3f::all( std::numeric_limits<float>::quiet_NaN() ) );
281  cv::Mat depth_map_cpu = left_depth_map.getMat(cv::ACCESS_READ);
282  float* depth_vec = (float*)(&(depth_map_cpu.data[0]));
283 
284 #pragma omp parallel for
285  for(size_t idx=0; idx<buf_size;idx++ )
286  {
287  size_t r = idx/left_depth_map.cols;
288  size_t c = idx%left_depth_map.cols;
289  double depth = static_cast<double>(depth_vec[idx]);
290  //std::cout << depth << " ";
291  if(!isinf(depth) && depth >=0 && depth > stereoPar.minDepth_mm && depth < stereoPar.maxDepth_mm)
292  {
293  buffer[idx].val[2] = depth; // Z
294  buffer[idx].val[0] = (c-cx)*depth/fx; // X
295  buffer[idx].val[1] = (r-cy)*depth/fy; // Y
296  }
297  }
298 
299  cloudMat = cv::Mat( left_depth_map.rows, left_depth_map.cols, CV_64FC3, &buffer[0] ).clone();
300 
301  double pc_elapsed = stereo_clock.toc();
302  std::stringstream pcElabInfo;
303 // pcElabInfo << "Point cloud processing: " << pc_elapsed << " sec - Freq: " << 1./pc_elapsed;
304  //std::cout << pcElabInfo.str() << std::endl;
305  // <---- Create Point Cloud
306  }
307 
308 
309  // ----> Keyboard handling
310  int key = cv::waitKey( 5 );
311  if(key=='q' || key=='Q') // Quit
312  break;
313  // <---- Keyboard handling
314 
315 #ifdef HAVE_OPENCV_VIZ
316  // ----> Show Point Cloud
317  cv::viz::WCloud cloudWidget( cloudMat, left_rect );
318  cloudWidget.setRenderingProperty( cv::viz::POINT_SIZE, 1 );
319  pc_viewer.showWidget( "Point Cloud", cloudWidget );
320  pc_viewer.spinOnce(1);
321 
322  if(pc_viewer.wasStopped())
323  break;
324  // <---- Show Point Cloud
325 #endif
326  }
327 
328  return EXIT_SUCCESS;
329 }
The StereoSgbmPar class is used to store/retrieve the stereo matching parameters.
Definition: stereo.hpp:20
int P1
[default: 24*blockSize*blockSize] The first parameter controlling the disparity smoothness....
Definition: stereo.hpp:57
int disp12MaxDiff
[default: 96] Maximum allowed difference (in integer pixel units) in the left-right disparity check....
Definition: stereo.hpp:59
int speckleWindowSize
[default: 255] Maximum size of smooth disparity regions to consider their noise speckles and invalida...
Definition: stereo.hpp:62
int uniquenessRatio
[default: 5] Margin in percentage by which the best (minimum) computed cost function value should "wi...
Definition: stereo.hpp:61
double minDepth_mm
[default: 300] Minimum value of depth for the extracted depth map
Definition: stereo.hpp:65
int minDisparity
[default: 0] Minimum possible disparity value. Normally, it is zero but sometimes rectification algor...
Definition: stereo.hpp:54
bool save()
save stereo matching parameters
Definition: stereo.hpp:120
bool load()
load stereo matching parameters
Definition: stereo.hpp:87
int numDisparities
[default: 96] Maximum disparity minus minimum disparity. The value is always greater than zero....
Definition: stereo.hpp:55
int mode
Set it to StereoSGBM::MODE_HH to run the full-scale two-pass dynamic programming algorithm....
Definition: stereo.hpp:56
int speckleRange
[default: 1] Maximum disparity variation within each connected component. If you do speckle filtering...
Definition: stereo.hpp:63
int blockSize
[default: 3] Matched block size. It must be an odd number >=1 . Normally, it should be somewhere in t...
Definition: stereo.hpp:53
double maxDepth_mm
[default: 10000] Maximum value of depth for the extracted depth map
Definition: stereo.hpp:66
void print()
print the current stereo matching parameters on standard output
Definition: stereo.hpp:150
int preFilterCap
[default: 63] Truncation value for the prefiltered image pixels. The algorithm first computes x-deriv...
Definition: stereo.hpp:60
int P2
[default: 4*PI]The second parameter controlling the disparity smoothness. The larger the values are,...
Definition: stereo.hpp:58
Stop Timer used to measure time intervals.
Definition: stopwatch.hpp:34
double toc()
Calculates the seconds elapsed from the last tic.
Definition: stopwatch.hpp:55
The VideoCapture class provides image grabbing functions and settings control for all the Stereolabs ...
bool initCalibration(std::string calibration_file, cv::Size2i image_size, cv::Mat &map_left_x, cv::Mat &map_left_y, cv::Mat &map_right_x, cv::Mat &map_right_y, cv::Mat &cameraMatrix_left, cv::Mat &cameraMatrix_right, double *baseline=nullptr)
void showImage(std::string name, cv::UMat &img, sl_oc::video::RESOLUTION res, bool change_name=true, std::string info="")
Rescale the OpenCV T-API images [cv::UMat] according to the selected resolution to better display the...
Definition: ocv_display.hpp:27
bool downloadCalibrationFile(unsigned int serial_number, std::string &calibration_file)
@ FPS_30
30 Frames per second. Not available for RESOLUTION::HD2K.
VERBOSITY
Definition: defines.hpp:85
@ INFO
Definition: defines.hpp:89
The Frame struct containing the acquired video frames.
uint64_t timestamp
Timestamp in nanoseconds.
uint16_t height
Frame height.
uint16_t width
Frame width.
uint8_t * data
Frame data in YUV 4:2:2 format.
The camera configuration parameters.
RESOLUTION res
Camera resolution.
FPS fps
Frames per second.
cv::Mat left_raw
sl_oc::tools::StereoSgbmPar stereoPar
cv::Mat frameBGR
cv::Mat left_for_matcher
sl_oc::video::VideoParams params
cv::Mat right_raw
cv::Mat right_for_matcher
cv::Mat left_disp_vis
cv::Mat frameYUV
cv::Mat left_rect
cv::Mat left_disp
cv::Mat right_rect
cv::Ptr< cv::StereoSGBM > left_matcher

References sl_oc::tools::StereoSgbmPar::blockSize, sl_oc::video::Frame::data, sl_oc::tools::StereoSgbmPar::disp12MaxDiff, sl_oc::tools::downloadCalibrationFile(), sl_oc::video::VideoParams::fps, sl_oc::video::FPS_30, frameBGR, frameYUV, sl_oc::video::VideoCapture::getFrameSize(), sl_oc::video::VideoCapture::getLastFrame(), sl_oc::video::VideoCapture::getSerialNumber(), sl_oc::video::HD720, sl_oc::video::Frame::height, sl_oc::INFO, sl_oc::tools::initCalibration(), sl_oc::video::VideoCapture::initializeVideo(), left_disp, left_disp_vis, left_for_matcher, left_matcher, left_raw, left_rect, sl_oc::tools::StereoSgbmPar::load(), sl_oc::tools::StereoSgbmPar::maxDepth_mm, sl_oc::tools::StereoSgbmPar::minDepth_mm, sl_oc::tools::StereoSgbmPar::minDisparity, sl_oc::tools::StereoSgbmPar::mode, sl_oc::tools::StereoSgbmPar::numDisparities, sl_oc::tools::StereoSgbmPar::P1, sl_oc::tools::StereoSgbmPar::P2, params, sl_oc::tools::StereoSgbmPar::preFilterCap, sl_oc::tools::StereoSgbmPar::print(), sl_oc::video::VideoParams::res, right_for_matcher, right_raw, right_rect, sl_oc::tools::StereoSgbmPar::save(), sl_oc::tools::showImage(), sl_oc::tools::StereoSgbmPar::speckleRange, sl_oc::tools::StereoSgbmPar::speckleWindowSize, stereoPar, sl_oc::video::Frame::timestamp, sl_oc::tools::StopWatch::toc(), sl_oc::tools::StereoSgbmPar::uniquenessRatio, sl_oc::video::VideoParams::verbose, sl_oc::video::VGA, and sl_oc::video::Frame::width.