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

Example of how to use the VideoCapture class to get and rectify raw video frames downloading calibration parameters from Stereolabs servers and then use OpenCV and T-API to extract the disparity map, the depth map, and finally generate the RGB point cloud.

//
// Copyright (c) 2021, STEREOLABS.
//
// All rights reserved.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
//
// ----> Includes
#include <iostream>
#include <sstream>
#include <string>
#include "videocapture.hpp"
// OpenCV includes
#include <opencv2/opencv.hpp>
//#undef HAVE_OPENCV_VIZ // Uncomment if cannot use Viz3D for point cloud rendering
#ifdef HAVE_OPENCV_VIZ
#include <opencv2/viz.hpp>
#include <opencv2/viz/viz3d.hpp>
#endif
// Sample includes
#include "calibration.hpp"
#include "stopwatch.hpp"
#include "stereo.hpp"
#include "ocv_display.hpp"
// <---- Includes
#define USE_OCV_TAPI // Comment to use "normal" cv::Mat instead of CV::UMat
#define USE_HALF_SIZE_DISP // Comment to compute depth matching on full image frames
int main(int argc, char *argv[])
{
// ----> Silence unused warning
(void)argc;
(void)argv;
// <---- Silence unused warning
// ----> Set Video parameters
#ifdef EMBEDDED_ARM
#else
#endif
params.verbose = verbose;
// <---- Set Video parameters
// ----> Create Video Capture
if( !cap.initializeVideo(-1) )
{
std::cerr << "Cannot open camera video capture" << std::endl;
std::cerr << "See verbosity level for more details." << std::endl;
return EXIT_FAILURE;
}
int sn = cap.getSerialNumber();
std::cout << "Connected to camera sn: " << sn << std::endl;
// <---- Create Video Capture
// ----> Retrieve calibration file from Stereolabs server
std::string calibration_file;
// ZED Calibration
unsigned int serial_number = sn;
// Download camera calibration file
if( !sl_oc::tools::downloadCalibrationFile(serial_number, calibration_file) )
{
std::cerr << "Could not load calibration file from Stereolabs servers" << std::endl;
return EXIT_FAILURE;
}
std::cout << "Calibration file found. Loading..." << std::endl;
// ----> Frame size
int w,h;
cap.getFrameSize(w,h);
// <---- Frame size
// ----> Initialize calibration
cv::Mat map_left_x, map_left_y;
cv::Mat map_right_x, map_right_y;
cv::Mat cameraMatrix_left, cameraMatrix_right;
double baseline=0;
sl_oc::tools::initCalibration(calibration_file, cv::Size(w/2,h), map_left_x, map_left_y, map_right_x, map_right_y,
cameraMatrix_left, cameraMatrix_right, &baseline);
double fx = cameraMatrix_left.at<double>(0,0);
double fy = cameraMatrix_left.at<double>(1,1);
double cx = cameraMatrix_left.at<double>(0,2);
double cy = cameraMatrix_left.at<double>(1,2);
std::cout << " Camera Matrix L: \n" << cameraMatrix_left << std::endl << std::endl;
std::cout << " Camera Matrix R: \n" << cameraMatrix_right << std::endl << std::endl;
#ifdef USE_OCV_TAPI
cv::UMat map_left_x_gpu = map_left_x.getUMat(cv::ACCESS_READ,cv::USAGE_ALLOCATE_DEVICE_MEMORY);
cv::UMat map_left_y_gpu = map_left_y.getUMat(cv::ACCESS_READ,cv::USAGE_ALLOCATE_DEVICE_MEMORY);
cv::UMat map_right_x_gpu = map_right_x.getUMat(cv::ACCESS_READ,cv::USAGE_ALLOCATE_DEVICE_MEMORY);
cv::UMat map_right_y_gpu = map_right_y.getUMat(cv::ACCESS_READ,cv::USAGE_ALLOCATE_DEVICE_MEMORY);
#endif
// ----> Initialize calibration
// ----> Declare OpenCV images
#ifdef USE_OCV_TAPI
cv::UMat frameYUV; // Full frame side-by-side in YUV 4:2:2 format
cv::UMat frameBGR(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Full frame side-by-side in BGR format
cv::UMat left_raw(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Left unrectified image
cv::UMat right_raw(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Right unrectified image
cv::UMat left_rect(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Left rectified image
cv::UMat right_rect(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Right rectified image
cv::UMat left_for_matcher(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Left image for the stereo matcher
cv::UMat right_for_matcher(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Right image for the stereo matcher
cv::UMat left_disp_half(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Half sized disparity map
cv::UMat left_disp(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Full output disparity
cv::UMat left_disp_float(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Final disparity map in float32
cv::UMat left_disp_image(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Normalized and color remapped disparity map to be displayed
cv::UMat left_depth_map(cv::USAGE_ALLOCATE_DEVICE_MEMORY); // Depth map in float32
#else
#endif
// <---- Declare OpenCV images
// ----> Stereo matcher initialization
//Note: you can use the tool 'zed_open_capture_depth_tune_stereo' to tune the parameters and save them to YAML
if(!stereoPar.load())
{
stereoPar.save(); // Save default parameters.
}
cv::Ptr<cv::StereoSGBM> left_matcher = cv::StereoSGBM::create(stereoPar.minDisparity,stereoPar.numDisparities,stereoPar.blockSize);
left_matcher->setMinDisparity(stereoPar.minDisparity);
left_matcher->setNumDisparities(stereoPar.numDisparities);
left_matcher->setDisp12MaxDiff(stereoPar.disp12MaxDiff);
left_matcher->setPreFilterCap(stereoPar.preFilterCap);
left_matcher->setUniquenessRatio(stereoPar.uniquenessRatio);
left_matcher->setSpeckleWindowSize(stereoPar.speckleWindowSize);
left_matcher->setSpeckleRange(stereoPar.speckleRange);
// <---- Stereo matcher initialization
// ----> Point Cloud
cv::Mat cloudMat;
#ifdef HAVE_OPENCV_VIZ
cv::viz::Viz3d pc_viewer = cv::viz::Viz3d( "Point Cloud" );
#endif
// <---- Point Cloud
uint64_t last_ts=0; // Used to check new frame arrival
// Infinite video grabbing loop
while (1)
{
// Get a new frame from camera
const sl_oc::video::Frame frame = cap.getLastFrame();
// ----> If the frame is valid we can convert, rectify and display it
if(frame.data!=nullptr && frame.timestamp!=last_ts)
{
last_ts = frame.timestamp;
// ----> Conversion from YUV 4:2:2 to BGR for visualization
#ifdef USE_OCV_TAPI
cv::Mat frameYUV_cpu = cv::Mat( frame.height, frame.width, CV_8UC2, frame.data );
frameYUV = frameYUV_cpu.getUMat(cv::ACCESS_READ,cv::USAGE_ALLOCATE_HOST_MEMORY);
#else
frameYUV = cv::Mat( frame.height, frame.width, CV_8UC2, frame.data );
#endif
cv::cvtColor(frameYUV,frameBGR,cv::COLOR_YUV2BGR_YUYV);
// <---- Conversion from YUV 4:2:2 to BGR for visualization
// ----> Extract left and right images from side-by-side
left_raw = frameBGR(cv::Rect(0, 0, frameBGR.cols / 2, frameBGR.rows));
right_raw = frameBGR(cv::Rect(frameBGR.cols / 2, 0, frameBGR.cols / 2, frameBGR.rows));
// <---- Extract left and right images from side-by-side
// ----> Apply rectification
#ifdef USE_OCV_TAPI
cv::remap(left_raw, left_rect, map_left_x_gpu, map_left_y_gpu, cv::INTER_AREA );
cv::remap(right_raw, right_rect, map_right_x_gpu, map_right_y_gpu, cv::INTER_AREA );
#else
cv::remap(left_raw, left_rect, map_left_x, map_left_y, cv::INTER_AREA );
cv::remap(right_raw, right_rect, map_right_x, map_right_y, cv::INTER_AREA );
#endif
double remap_elapsed = remap_clock.toc();
std::stringstream remapElabInfo;
remapElabInfo << "Rectif. processing: " << remap_elapsed << " sec - Freq: " << 1./remap_elapsed;
// <---- Apply rectification
// ----> Stereo matching
double resize_fact = 1.0;
#ifdef USE_HALF_SIZE_DISP
resize_fact = 0.5;
// Resize the original images to improve performances
cv::resize(left_rect, left_for_matcher, cv::Size(), resize_fact, resize_fact, cv::INTER_AREA);
cv::resize(right_rect, right_for_matcher, cv::Size(), resize_fact, resize_fact, cv::INTER_AREA);
#else
left_for_matcher = left_rect; // No data copy
right_for_matcher = right_rect; // No data copy
#endif
// Apply stereo matching
left_matcher->compute(left_for_matcher, right_for_matcher,left_disp_half);
left_disp_half.convertTo(left_disp_float,CV_32FC1);
cv::multiply(left_disp_float,1./16.,left_disp_float); // Last 4 bits of SGBM disparity are decimal
#ifdef USE_HALF_SIZE_DISP
cv::multiply(left_disp_float,2.,left_disp_float); // Last 4 bits of SGBM disparity are decimal
cv::UMat tmp = left_disp_float; // Required for OpenCV 3.2
cv::resize(tmp, left_disp_float, cv::Size(), 1./resize_fact, 1./resize_fact, cv::INTER_AREA);
#else
left_disp = left_disp_float;
#endif
double elapsed = stereo_clock.toc();
std::stringstream stereoElabInfo;
stereoElabInfo << "Stereo processing: " << elapsed << " sec - Freq: " << 1./elapsed;
// <---- Stereo matching
// ----> Show frames
sl_oc::tools::showImage("Right rect.", right_rect, params.res,true, remapElabInfo.str());
sl_oc::tools::showImage("Left rect.", left_rect, params.res,true, remapElabInfo.str());
// <---- Show frames
// ----> Show disparity image
cv::add(left_disp_float,-static_cast<double>(stereoPar.minDisparity-1),left_disp_float); // Minimum disparity offset correction
cv::multiply(left_disp_float,1./stereoPar.numDisparities,left_disp_image,255., CV_8UC1 ); // Normalization and rescaling
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
sl_oc::tools::showImage("Disparity", left_disp_image, params.res,true, stereoElabInfo.str());
// <---- Show disparity image
// ----> Extract Depth map
// The DISPARITY MAP can be now transformed in DEPTH MAP using the formula
// depth = (f * B) / disparity
// where 'f' is the camera focal, 'B' is the camera baseline, 'disparity' is the pixel disparity
double num = static_cast<double>(fx*baseline);
cv::divide(num,left_disp_float,left_depth_map);
float central_depth = left_depth_map.getMat(cv::ACCESS_READ).at<float>(left_depth_map.rows/2, left_depth_map.cols/2 );
std::cout << "Depth of the central pixel: " << central_depth << " mm" << std::endl;
// <---- Extract Depth map
// ----> Create Point Cloud
size_t buf_size = static_cast<size_t>(left_depth_map.cols * left_depth_map.rows);
std::vector<cv::Vec3d> buffer( buf_size, cv::Vec3f::all( std::numeric_limits<float>::quiet_NaN() ) );
cv::Mat depth_map_cpu = left_depth_map.getMat(cv::ACCESS_READ);
float* depth_vec = (float*)(&(depth_map_cpu.data[0]));
#pragma omp parallel for
for(size_t idx=0; idx<buf_size;idx++ )
{
size_t r = idx/left_depth_map.cols;
size_t c = idx%left_depth_map.cols;
double depth = static_cast<double>(depth_vec[idx]);
//std::cout << depth << " ";
if(!isinf(depth) && depth >=0 && depth > stereoPar.minDepth_mm && depth < stereoPar.maxDepth_mm)
{
buffer[idx].val[2] = depth; // Z
buffer[idx].val[0] = (c-cx)*depth/fx; // X
buffer[idx].val[1] = (r-cy)*depth/fy; // Y
}
}
cloudMat = cv::Mat( left_depth_map.rows, left_depth_map.cols, CV_64FC3, &buffer[0] ).clone();
double pc_elapsed = stereo_clock.toc();
std::stringstream pcElabInfo;
// pcElabInfo << "Point cloud processing: " << pc_elapsed << " sec - Freq: " << 1./pc_elapsed;
//std::cout << pcElabInfo.str() << std::endl;
// <---- Create Point Cloud
}
// ----> Keyboard handling
int key = cv::waitKey( 5 );
if(key=='q' || key=='Q') // Quit
break;
// <---- Keyboard handling
#ifdef HAVE_OPENCV_VIZ
// ----> Show Point Cloud
cv::viz::WCloud cloudWidget( cloudMat, left_rect );
cloudWidget.setRenderingProperty( cv::viz::POINT_SIZE, 1 );
pc_viewer.showWidget( "Point Cloud", cloudWidget );
pc_viewer.spinOnce(1);
if(pc_viewer.wasStopped())
break;
// <---- Show Point Cloud
#endif
}
return EXIT_SUCCESS;
}
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 ...
const Frame & getLastFrame(uint64_t timeout_msec=100)
Get the last received camera image.
void getFrameSize(int &width, int &height)
Get the size of the camera frame.
bool initializeVideo(int devId=-1)
Open a ZED camera using the specified ID or searching for the first available.
int getSerialNumber()
Retrieve the serial number of the connected camera.
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.
int main(int argc, char *argv[])
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