├── .github ├── ISSUE_TEMPLATE │ ├── config.yml │ ├── 1_feature_request.yml │ └── 2_bug_report.yml └── workflows │ └── stale_issues.yml ├── cpp ├── include │ └── SaveDepth.hpp ├── CMakeLists.txt ├── README.md └── src │ ├── SaveDepth.cpp │ └── main.cpp ├── LICENSE ├── python ├── README.md └── zed-opencv.py └── README.md /.github/ISSUE_TEMPLATE/config.yml: -------------------------------------------------------------------------------- 1 | blank_issues_enabled: false 2 | contact_links: 3 | - name: Online Documentation 4 | url: https://www.stereolabs.com/docs/ 5 | about: Check out the Stereolabs documentation for answers to common questions. 6 | - name: Stereolabs Community 7 | url: https://community.stereolabs.com/ 8 | about: Ask questions, request features & discuss with other users and developers. 9 | - name: Stereolabs Twitter 10 | url: https://twitter.com/Stereolabs3D 11 | about: The official Stereolabs Twitter account to ask questions, comment our products and share your projects with the ZED community. 12 | 13 | -------------------------------------------------------------------------------- /cpp/include/SaveDepth.hpp: -------------------------------------------------------------------------------- 1 | #ifndef __SAVE_DEPTH_HPP__ 2 | #define __SAVE_DEPTH_HPP__ 3 | 4 | #define NOMINMAX 5 | 6 | #include 7 | #include 8 | #include 9 | #include 10 | #include 11 | 12 | #include 13 | #include 14 | 15 | const std::string helpString = "[d] Save Depth, [n] Change Depth format, [p] Save Point Cloud, [m] Change Point Cloud format, [q] Quit"; 16 | const std::string prefixPointCloud = "Cloud_"; // Default PointCloud output file prefix 17 | const std::string prefixDepth = "Depth_"; // Default Depth image output file prefix 18 | const std::string path = "./"; 19 | 20 | void savePointCloud(sl::Camera& zed, std::string filename); 21 | void saveDepth(sl::Camera& zed, std::string filename); 22 | void saveSbSImage(sl::Camera& zed, std::string filename); 23 | 24 | void processKeyEvent(sl::Camera& zed, char &key); 25 | 26 | #endif 27 | -------------------------------------------------------------------------------- /.github/workflows/stale_issues.yml: -------------------------------------------------------------------------------- 1 | name: 'Stale issue handler' 2 | on: 3 | workflow_dispatch: 4 | schedule: 5 | - cron: '00 00 * * *' 6 | 7 | jobs: 8 | stale: 9 | runs-on: ubuntu-latest 10 | steps: 11 | - uses: actions/stale@main 12 | id: stale 13 | with: 14 | stale-issue-message: 'This issue is stale because it has been open 30 days with no activity. Remove stale label or comment otherwise it will be automatically closed in 5 days' 15 | stale-pr-message: 'This PR is stale because it has been open 30 days with no activity. Remove stale label or comment otherwise it will be automatically closed in 5 days' 16 | days-before-stale: 30 17 | days-before-close: 5 18 | operations-per-run: 1500 19 | exempt-issue-labels: 'feature_request' 20 | exempt-pr-labels: 'feature_request' 21 | enable-statistics: 'true' 22 | close-issue-label: 'closed_for_stale' 23 | close-pr-label: 'closed_for_stale' 24 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | MIT License 2 | 3 | Copyright (c) 2018 Stereolabs 4 | 5 | Permission is hereby granted, free of charge, to any person obtaining a copy 6 | of this software and associated documentation files (the "Software"), to deal 7 | in the Software without restriction, including without limitation the rights 8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 9 | copies of the Software, and to permit persons to whom the Software is 10 | furnished to do so, subject to the following conditions: 11 | 12 | The above copyright notice and this permission notice shall be included in all 13 | copies or substantial portions of the Software. 14 | 15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE 21 | SOFTWARE. 22 | 23 | -------------------------------------------------------------------------------- /cpp/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | CMAKE_MINIMUM_REQUIRED(VERSION 2.4) 2 | PROJECT(ZED_with_OpenCV) 3 | 4 | option(LINK_SHARED_ZED "Link with the ZED SDK shared executable" ON) 5 | 6 | if (NOT LINK_SHARED_ZED AND MSVC) 7 | message(FATAL_ERROR "LINK_SHARED_ZED OFF : ZED SDK static libraries not available on Windows") 8 | endif() 9 | 10 | if(COMMAND cmake_policy) 11 | cmake_policy(SET CMP0003 OLD) 12 | cmake_policy(SET CMP0015 OLD) 13 | endif(COMMAND cmake_policy) 14 | 15 | SET(EXECUTABLE_OUTPUT_PATH ".") 16 | 17 | find_package(ZED 3 REQUIRED) 18 | find_package(OpenCV 4 REQUIRED) 19 | find_package(CUDA ${ZED_CUDA_VERSION} EXACT REQUIRED) 20 | 21 | IF(NOT WIN32) 22 | add_definitions(-Wno-format-extra-args) 23 | SET(SPECIAL_OS_LIBS "pthread" "X11") 24 | ENDIF() 25 | 26 | include_directories(${CUDA_INCLUDE_DIRS}) 27 | include_directories(${ZED_INCLUDE_DIRS}) 28 | include_directories(${OpenCV_INCLUDE_DIRS}) 29 | include_directories(${CMAKE_CURRENT_SOURCE_DIR}/include) 30 | 31 | link_directories(${ZED_LIBRARY_DIR}) 32 | link_directories(${OpenCV_LIBRARY_DIRS}) 33 | link_directories(${CUDA_LIBRARY_DIRS}) 34 | 35 | FILE(GLOB_RECURSE SRC_FILES src/*.cpp) 36 | FILE(GLOB_RECURSE HDR_FILES include/*.hpp) 37 | 38 | ADD_EXECUTABLE(${PROJECT_NAME} ${HDR_FILES} ${SRC_FILES}) 39 | add_definitions(-std=c++14 -O3) 40 | 41 | if (LINK_SHARED_ZED) 42 | SET(ZED_LIBS ${ZED_LIBRARIES} ${CUDA_CUDA_LIBRARY} ${CUDA_CUDART_LIBRARY}) 43 | else() 44 | SET(ZED_LIBS ${ZED_STATIC_LIBRARIES} ${CUDA_CUDA_LIBRARY} ${CUDA_LIBRARY}) 45 | endif() 46 | 47 | TARGET_LINK_LIBRARIES(${PROJECT_NAME} ${ZED_LIBS} ${OpenCV_LIBRARIES}) 48 | -------------------------------------------------------------------------------- /.github/ISSUE_TEMPLATE/1_feature_request.yml: -------------------------------------------------------------------------------- 1 | name: Feature request 🧭 2 | description: Suggest an idea for this project. 3 | labels: "feature request" 4 | body: 5 | - type: markdown 6 | attributes: 7 | value: | 8 | # Welcome 👋 9 | 10 | Thanks for taking the time to fill out this feature request module. 11 | Please fill out each section below. This info allows Stereolabs developers to correctly evaluate your request. 12 | 13 | Useful Links: 14 | - Documentation: https://www.stereolabs.com/docs/ 15 | - Stereolabs support: https://support.stereolabs.com/hc/en-us/ 16 | - type: checkboxes 17 | attributes: 18 | label: Preliminary Checks 19 | description: Please make sure that you verify each checkbox and follow the instructions for them. 20 | options: 21 | - label: "This issue is not a duplicate. Before opening a new issue, please search existing issues." 22 | required: true 23 | - label: "This issue is not a question, bug report, or anything other than a feature request directly related to this project." 24 | required: true 25 | - type: textarea 26 | attributes: 27 | label: Proposal 28 | description: "What would you like to have as a new feature?" 29 | placeholder: "A clear and concise description of what you want to happen." 30 | validations: 31 | required: true 32 | - type: textarea 33 | attributes: 34 | label: Use-Case 35 | description: "How would this help you?" 36 | placeholder: "Tell us more what you'd like to achieve." 37 | validations: 38 | required: false 39 | - type: textarea 40 | id: anything-else 41 | attributes: 42 | label: Anything else? 43 | description: "Let us know if you have anything else to share" 44 | -------------------------------------------------------------------------------- /python/README.md: -------------------------------------------------------------------------------- 1 | # Stereolabs ZED - OpenCV Python 2 | 3 | This sample is the perfect place to get started coding with the ZED and OpenCV. It shows how to: 4 | 5 | - Capture image, depth and point cloud from the ZED. 6 | - Convert image and depth map to compatible 32-bits float OpenCV matrix. 7 | - Display video and depth with OpenCV. 8 | - Adjust several depth parameters: depth sensing mode, quality, units, resolution. 9 | - Save side by side image, depth image and point cloud in various formats 10 | 11 | ## Getting started 12 | 13 | - First, download the latest version of the ZED SDK on [stereolabs.com](https://www.stereolabs.com). 14 | - For more information, read the ZED [API documentation](https://www.stereolabs.com/developers/documentation/API/). 15 | 16 | ### Prerequisites 17 | 18 | - Windows 7 64bits or later, Ubuntu 16.04 or 18.04 19 | - [ZED SDK](https://www.stereolabs.com/developers/) and its dependencies ([CUDA](https://developer.nvidia.com/cuda-downloads), [OpenCV](https://github.com/opencv/opencv/releases)) 20 | - [ZED Python API](https://github.com/stereolabs/zed-python-api), check the README of the github to know how to install it 21 | 22 | ## Run the program 23 | 24 | Open a termial and simply execute the python script. 25 | 26 | ### Windows 27 | ``` 28 | python zed_opencv.py [path to SVO file] 29 | ``` 30 | 31 | ### Linux 32 | ``` 33 | python3 zed_opencv.py [path to SVO file] 34 | ``` 35 | 36 | You can optionally provide an SVO file path (recorded stereo video of the ZED) 37 | 38 | ### Keyboard shortcuts 39 | 40 | This table lists keyboard shortcuts that you can use in the sample application. 41 | 42 | Parameter | Description | Hotkey 43 | ---------------------|------------------------------------|------------------------------------------------- 44 | Save Side by Side | Save side by side image. | 's' 45 | Save Depth | Save depth image. | 'p' 46 | Save Point Cloud | Save 3D point cloud. | 'd' 47 | Switch cloud format | Toggle between point cloud formats. | 'm' 48 | Switch depth format | Toggle between depth image formats. | 'n' 49 | Exit | Quit the application. | 'q' 50 | -------------------------------------------------------------------------------- /cpp/README.md: -------------------------------------------------------------------------------- 1 | # Stereolabs ZED - OpenCV 2 | 3 | This sample is the perfect place to get started coding with the ZED and OpenCV. It shows how to: 4 | 5 | - Capture image, depth and point cloud from the ZED. 6 | - Convert image and depth map to compatible 32-bits float OpenCV matrix. 7 | - Display video and depth with OpenCV. 8 | - Adjust several depth parameters: depth sensing mode, quality, units, resolution. 9 | - Save side by side image, depth image and point cloud in various formats 10 | 11 | ## Getting started 12 | 13 | - First, download the latest version of the ZED SDK on [stereolabs.com](https://www.stereolabs.com). 14 | - For more information, read the ZED [API documentation](https://www.stereolabs.com/developers/documentation/API/). 15 | 16 | ### Prerequisites 17 | 18 | - Windows 10, Ubuntu LTS 19 | - [ZED SDK](https://www.stereolabs.com/developers/) and its dependencies ([CUDA](https://developer.nvidia.com/cuda-downloads), [OpenCV](https://github.com/opencv/opencv/releases)) 20 | 21 | ## Build the program 22 | 23 | Download the sample and follow the instructions below: [More](https://www.stereolabs.com/docs/getting-started/application-development/) 24 | 25 | #### Build for Windows 26 | 27 | - Create a "build" folder in the source folder 28 | - Open cmake-gui and select the source and build folders 29 | - Generate the Visual Studio `Win64` solution 30 | - Open the resulting solution and change configuration to `Release` 31 | - Build solution 32 | 33 | #### Build for Linux 34 | 35 | Open a terminal in the sample directory and execute the following command: 36 | 37 | mkdir build 38 | cd build 39 | cmake .. 40 | make 41 | 42 | ## Run the program 43 | 44 | - Navigate to the build directory and launch the executable file 45 | - Or open a terminal in the build directory and run the sample : 46 | 47 | ./ZED\ with\ OpenCV [path to SVO file] 48 | 49 | You can optionally provide an SVO file path (recorded stereo video of the ZED). 50 | 51 | ### Keyboard shortcuts 52 | 53 | This table lists keyboard shortcuts that you can use in the sample application. 54 | 55 | Parameter | Description | Hotkey 56 | ---------------------|------------------------------------|------------------------------------------------- 57 | Save Side by Side | Save side by side image. | 's' 58 | Save Depth | Save depth image. | 'p' 59 | Save Point Cloud | Save 3D point cloud. | 'd' 60 | Switch cloud format | Toggle between point cloud formats. | 'm' 61 | Switch depth format | Toggle between depth image formats. | 'n' 62 | Exit | Quit the application. | 'q' 63 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Stereolabs ZED - OpenCV 2 | 3 | This sample is the perfect place to get started coding with the ZED and OpenCV. It shows how to: 4 | 5 | - Capture image, depth and point cloud from the ZED. 6 | - Convert image and depth map to compatible 32-bits float OpenCV matrix. 7 | - Display video and depth with OpenCV. 8 | - Adjust several depth parameters: depth sensing mode, quality, units, resolution. 9 | - Save side by side image, depth image and point cloud in various formats 10 | 11 | ## Getting started 12 | 13 | - First, download the latest version of the ZED SDK on [stereolabs.com](https://www.stereolabs.com). 14 | - For more information, read the ZED [Documentation](https://www.stereolabs.com/docs/) and [API documentation](https://www.stereolabs.com/docs/api/) or our [Community page](https://community.stereolabs.com) 15 | 16 | ### Prerequisites 17 | 18 | - Windows 10, Ubuntu LTS 19 | - [ZED SDK](https://www.stereolabs.com/developers/) and its dependencies ([CUDA](https://developer.nvidia.com/cuda-downloads), [OpenCV](https://github.com/opencv/opencv/releases)) 20 | 21 | OpenCV can be installed from source on Linux, please refer to this [guide](https://www.stereolabs.com/docs/getting-started/application-development/#building-on-linux-and-jetson) to proceed with the installation. 22 | 23 | ### C++ 24 | 25 | Read the [guide](./cpp) to learn how to build and launch this sample in C++. 26 | 27 | ### Python 28 | 29 | Read the [guide](./python) to learn how to build and launch this sample in Python. 30 | 31 | 32 | ## Installing OpenCV 33 | 34 | ### Installing OpenCV on Windows 35 | 36 | OpenCV provides already compiled binaries, it can be downloaded at https://opencv.org/releases/ 37 | 38 | ### Installing OpenCV on Linux 39 | 40 | Some sample can require OpenCV, here is a tutorial on how to install it. 41 | 42 | OpenCV can be downloaded at this location : https://opencv.org/releases/ 43 | 44 | For a more detailed OpenCV tutorial installation, [refer to the opencv documention](https://docs.opencv.org/4.1.0/d7/d9f/tutorial_linux_install.html). 45 | 46 | #### Installation steps 47 | 48 | - Install the required dependencies 49 | 50 | ```bash 51 | sudo apt-get install build-essential cmake libgtk2.0-dev pkg-config libavcodec-dev libavformat-dev libswscale-dev 52 | ``` 53 | 54 | - Download source archive from http://opencv.org/releases.html and extract it 55 | 56 | ```bash 57 | wget https://github.com/opencv/opencv/archive/4.1.0.zip -O /tmp/opencv_src.zip 58 | cd ~/ 59 | unzip /tmp/opencv_src.zip ; rm /tmp/opencv_src.zip 60 | ``` 61 | 62 | - Navigate to the extracted sources, create a temporary build directory and enter it. For example, 63 | 64 | ```bash 65 | cd ~/opencv-* 66 | mkdir build 67 | cd build 68 | ``` 69 | 70 | - Run cmake 71 | 72 | ```bash 73 | cmake -D CMAKE_BUILD_TYPE=Release -D CMAKE_INSTALL_PREFIX=/usr/local -DBUILD_TESTS=OFF -DBUILD_PERF_TESTS=OFF -DBUILD_EXAMPLES=OFF -DBUILD_JAVA=OFF -DWITH_OPENGL=ON .. 74 | ``` 75 | 76 | - Execute make. The compilation can take a while 77 | 78 | ```bash 79 | make -j$(nproc) 80 | ``` 81 | 82 | - Install the libraries 83 | 84 | ```bash 85 | sudo make install 86 | ``` 87 | 88 | ## Support 89 | If you need assistance go to our Community site at https://community.stereolabs.com/ 90 | -------------------------------------------------------------------------------- /.github/ISSUE_TEMPLATE/2_bug_report.yml: -------------------------------------------------------------------------------- 1 | name: Bug Report 🐛 2 | description: Something isn't working as expected? Report your bugs here. 3 | labels: "bug" 4 | body: 5 | - type: markdown 6 | attributes: 7 | value: | 8 | # Welcome 👋 9 | 10 | Thanks for taking the time to fill out this bug report. 11 | Please fill out each section below. This info allows Stereolabs developers to diagnose (and fix!) your issue as quickly as possible. Otherwise we might need to close the issue without e.g. clear reproduction steps. 12 | 13 | Bug reports also shoulnd't be used for generic questions, please use the [Stereolabs Community forum](https://community.stereolabs.com/) instead. 14 | 15 | Useful Links: 16 | - Documentation: https://www.stereolabs.com/docs/ 17 | - Stereolabs support: https://support.stereolabs.com/hc/en-us/ 18 | - type: checkboxes 19 | attributes: 20 | label: Preliminary Checks 21 | description: Please make sure that you verify each checkbox and follow the instructions for them. 22 | options: 23 | - label: "This issue is not a duplicate. Before opening a new issue, please search existing issues." 24 | required: true 25 | - label: "This issue is not a question, feature request, or anything other than a bug report directly related to this project." 26 | required: true 27 | - type: textarea 28 | attributes: 29 | label: Description 30 | description: Describe the issue that you're seeing. 31 | placeholder: Be as precise as you can. Feel free to share screenshots, videos, or data. The more information you provide the easier will be to provide you with a fast solution. 32 | validations: 33 | required: true 34 | - type: textarea 35 | attributes: 36 | label: Steps to Reproduce 37 | description: Clear steps describing how to reproduce the issue. 38 | value: | 39 | 1. 40 | 2. 41 | 3. 42 | ... 43 | validations: 44 | required: true 45 | - type: textarea 46 | attributes: 47 | label: Expected Result 48 | description: Describe what you expected to happen. 49 | validations: 50 | required: true 51 | - type: textarea 52 | attributes: 53 | label: Actual Result 54 | description: Describe what actually happened. 55 | validations: 56 | required: true 57 | - type: dropdown 58 | attributes: 59 | label: ZED Camera model 60 | description: What model of ZED camera are you using? 61 | options: 62 | - "ZED" 63 | - "ZED Mini" 64 | - "ZED2" 65 | - "ZED2i" 66 | validations: 67 | required: true 68 | - type: textarea 69 | attributes: 70 | label: Environment 71 | render: shell 72 | description: Useful information about your system. 73 | placeholder: | 74 | OS: Operating System 75 | CPU: e.g. ARM 76 | GPU: Nvidia Jetson Xavier NX 77 | ZED SDK version: e.g. v3.5.3 78 | Other info: e.g. ROS Melodic 79 | validations: 80 | required: true 81 | - type: textarea 82 | attributes: 83 | label: Anything else? 84 | description: Please add any other information or comment that you think may be useful for solving the problem 85 | placeholder: 86 | validations: 87 | required: false 88 | -------------------------------------------------------------------------------- /cpp/src/SaveDepth.cpp: -------------------------------------------------------------------------------- 1 | #include "SaveDepth.hpp" 2 | 3 | using namespace sl; 4 | using namespace std; 5 | 6 | int count_save = 0; 7 | int mode_PointCloud = 0; 8 | int mode_Depth = 0; 9 | int PointCloud_format; 10 | int Depth_format; 11 | 12 | std::string PointCloud_format_ext=".ply"; 13 | std::string Depth_format_ext=".png"; 14 | 15 | void setPointCloudFormatName(int format) { 16 | switch (format) { 17 | case 0: 18 | PointCloud_format_ext = ".xyz"; 19 | break; 20 | case 1: 21 | PointCloud_format_ext = ".pcd"; 22 | break; 23 | case 2: 24 | PointCloud_format_ext = ".ply"; 25 | break; 26 | case 3: 27 | PointCloud_format_ext = ".vtk"; 28 | break; 29 | default: 30 | break; 31 | } 32 | } 33 | 34 | void setDepthFormatName(int format) { 35 | switch (format) { 36 | case 0: 37 | Depth_format_ext = ".png"; 38 | break; 39 | case 1: 40 | Depth_format_ext = ".pfm"; 41 | break; 42 | case 2: 43 | Depth_format_ext = ".pgm"; 44 | break; 45 | default: 46 | break; 47 | } 48 | } 49 | 50 | void processKeyEvent(Camera& zed, char &key) { 51 | switch (key) { 52 | case 'd': 53 | case 'D': 54 | saveDepth(zed, path + prefixDepth + to_string(count_save)); 55 | break; 56 | 57 | case 'n': // Depth format 58 | case 'N': 59 | { 60 | mode_Depth++; 61 | Depth_format = (mode_Depth % 3); 62 | setDepthFormatName(Depth_format); 63 | std::cout << "Depth format: " << Depth_format_ext << std::endl; 64 | } 65 | break; 66 | 67 | case 'p': 68 | case 'P': 69 | savePointCloud(zed, path + prefixPointCloud + to_string(count_save)); 70 | break; 71 | 72 | 73 | case 'm': // Point cloud format 74 | case 'M': 75 | { 76 | mode_PointCloud++; 77 | PointCloud_format = (mode_PointCloud % 4); 78 | setPointCloudFormatName(PointCloud_format); 79 | std::cout << "Point Cloud format: " << PointCloud_format_ext << std::endl; 80 | } 81 | break; 82 | 83 | case 'h': // Print help 84 | case 'H': 85 | cout << helpString << endl; 86 | break; 87 | 88 | case 's': // Save side by side image 89 | case 'S': 90 | saveSbSImage(zed, std::string("ZED_image") + std::to_string(count_save) + std::string(".png")); 91 | break; 92 | } 93 | count_save++; 94 | } 95 | 96 | void savePointCloud(Camera& zed, std::string filename) { 97 | std::cout << "Saving Point Cloud... " << flush; 98 | 99 | sl::Mat point_cloud; 100 | zed.retrieveMeasure(point_cloud, sl::MEASURE::XYZRGBA); 101 | 102 | auto state = point_cloud.write((filename + PointCloud_format_ext).c_str()); 103 | 104 | if (state == ERROR_CODE::SUCCESS) 105 | std::cout << "Point Cloud has been saved under " << filename << PointCloud_format_ext << endl; 106 | else 107 | std::cout << "Failed to save point cloud... Please check that you have permissions to write at this location ("<< filename<<"). Re-run the sample with administrator rights under windows" << endl; 108 | } 109 | 110 | void saveDepth(Camera& zed, std::string filename) { 111 | std::cout << "Saving Depth Map... " << flush; 112 | 113 | sl::Mat depth; 114 | zed.retrieveMeasure(depth, sl::MEASURE::DEPTH); 115 | 116 | convertUnit(depth, zed.getInitParameters().coordinate_units, UNIT::MILLIMETER); 117 | auto state = depth.write((filename + Depth_format_ext).c_str()); 118 | 119 | if (state == ERROR_CODE::SUCCESS) 120 | std::cout << "Depth Map has been save under " << filename << Depth_format_ext << endl; 121 | else 122 | std::cout << "Failed to save depth map... Please check that you have permissions to write at this location (" << filename << "). Re-run the sample with administrator rights under windows" << endl; 123 | } 124 | 125 | void saveSbSImage(Camera& zed, std::string filename) { 126 | sl::Mat image_sbs; 127 | zed.retrieveImage(image_sbs, sl::VIEW::SIDE_BY_SIDE); 128 | 129 | auto state = image_sbs.write(filename.c_str()); 130 | 131 | if (state == sl::ERROR_CODE::SUCCESS) 132 | std::cout << "Side by Side image has been save under " << filename << endl; 133 | else 134 | std::cout << "Failed to save image... Please check that you have permissions to write at this location (" << filename << "). Re-run the sample with administrator rights under windows" << endl; 135 | } 136 | -------------------------------------------------------------------------------- /python/zed-opencv.py: -------------------------------------------------------------------------------- 1 | import sys 2 | import numpy as np 3 | import pyzed.sl as sl 4 | import cv2 5 | 6 | help_string = "[s] Save side by side image [d] Save Depth, [n] Change Depth format, [p] Save Point Cloud, [m] Change Point Cloud format, [q] Quit" 7 | prefix_point_cloud = "Cloud_" 8 | prefix_depth = "Depth_" 9 | path = "./" 10 | 11 | count_save = 0 12 | mode_point_cloud = 0 13 | mode_depth = 0 14 | point_cloud_format_ext = ".ply" 15 | depth_format_ext = ".png" 16 | 17 | def point_cloud_format_name(): 18 | global mode_point_cloud 19 | if mode_point_cloud > 3: 20 | mode_point_cloud = 0 21 | switcher = { 22 | 0: ".xyz", 23 | 1: ".pcd", 24 | 2: ".ply", 25 | 3: ".vtk", 26 | } 27 | return switcher.get(mode_point_cloud, "nothing") 28 | 29 | def depth_format_name(): 30 | global mode_depth 31 | if mode_depth > 2: 32 | mode_depth = 0 33 | switcher = { 34 | 0: ".png", 35 | 1: ".pfm", 36 | 2: ".pgm", 37 | } 38 | return switcher.get(mode_depth, "nothing") 39 | 40 | def save_point_cloud(zed, filename) : 41 | print("Saving Point Cloud...") 42 | tmp = sl.Mat() 43 | zed.retrieve_measure(tmp, sl.MEASURE.XYZRGBA) 44 | saved = (tmp.write(filename + point_cloud_format_ext) == sl.ERROR_CODE.SUCCESS) 45 | if saved : 46 | print("Done") 47 | else : 48 | print("Failed... Please check that you have permissions to write on disk") 49 | 50 | def save_depth(zed, filename) : 51 | print("Saving Depth Map...") 52 | tmp = sl.Mat() 53 | zed.retrieve_measure(tmp, sl.MEASURE.DEPTH) 54 | saved = (tmp.write(filename + depth_format_ext) == sl.ERROR_CODE.SUCCESS) 55 | if saved : 56 | print("Done") 57 | else : 58 | print("Failed... Please check that you have permissions to write on disk") 59 | 60 | def save_sbs_image(zed, filename) : 61 | 62 | image_sl_left = sl.Mat() 63 | zed.retrieve_image(image_sl_left, sl.VIEW.LEFT) 64 | image_cv_left = image_sl_left.get_data() 65 | 66 | image_sl_right = sl.Mat() 67 | zed.retrieve_image(image_sl_right, sl.VIEW.RIGHT) 68 | image_cv_right = image_sl_right.get_data() 69 | 70 | sbs_image = np.concatenate((image_cv_left, image_cv_right), axis=1) 71 | 72 | cv2.imwrite(filename, sbs_image) 73 | 74 | 75 | def process_key_event(zed, key) : 76 | global mode_depth 77 | global mode_point_cloud 78 | global count_save 79 | global depth_format_ext 80 | global point_cloud_format_ext 81 | 82 | if key == 100 or key == 68: 83 | save_depth(zed, path + prefix_depth + str(count_save)) 84 | count_save += 1 85 | elif key == 110 or key == 78: 86 | mode_depth += 1 87 | depth_format_ext = depth_format_name() 88 | print("Depth format: ", depth_format_ext) 89 | elif key == 112 or key == 80: 90 | save_point_cloud(zed, path + prefix_point_cloud + str(count_save)) 91 | count_save += 1 92 | elif key == 109 or key == 77: 93 | mode_point_cloud += 1 94 | point_cloud_format_ext = point_cloud_format_name() 95 | print("Point Cloud format: ", point_cloud_format_ext) 96 | elif key == 104 or key == 72: 97 | print(help_string) 98 | elif key == 115: 99 | save_sbs_image(zed, "ZED_image" + str(count_save) + ".png") 100 | count_save += 1 101 | else: 102 | a = 0 103 | 104 | def print_help() : 105 | print(" Press 's' to save Side by side images") 106 | print(" Press 'p' to save Point Cloud") 107 | print(" Press 'd' to save Depth image") 108 | print(" Press 'm' to switch Point Cloud format") 109 | print(" Press 'n' to switch Depth format") 110 | 111 | 112 | def main() : 113 | 114 | # Create a ZED camera object 115 | zed = sl.Camera() 116 | 117 | # Set configuration parameters 118 | input_type = sl.InputType() 119 | if len(sys.argv) >= 2 : 120 | input_type.set_from_svo_file(sys.argv[1]) 121 | init = sl.InitParameters(input_t=input_type) 122 | init.camera_resolution = sl.RESOLUTION.HD1080 123 | init.depth_mode = sl.DEPTH_MODE.PERFORMANCE 124 | init.coordinate_units = sl.UNIT.MILLIMETER 125 | 126 | # Open the camera 127 | err = zed.open(init) 128 | if err != sl.ERROR_CODE.SUCCESS : 129 | print(repr(err)) 130 | zed.close() 131 | exit(1) 132 | 133 | # Display help in console 134 | print_help() 135 | 136 | # Set runtime parameters after opening the camera 137 | runtime = sl.RuntimeParameters() 138 | 139 | # Prepare new image size to retrieve half-resolution images 140 | image_size = zed.get_camera_information().camera_configuration.resolution 141 | image_size.width = image_size.width /2 142 | image_size.height = image_size.height /2 143 | 144 | # Declare your sl.Mat matrices 145 | image_zed = sl.Mat(image_size.width, image_size.height, sl.MAT_TYPE.U8_C4) 146 | depth_image_zed = sl.Mat(image_size.width, image_size.height, sl.MAT_TYPE.U8_C4) 147 | point_cloud = sl.Mat() 148 | 149 | key = ' ' 150 | while key != 113 : 151 | err = zed.grab(runtime) 152 | if err == sl.ERROR_CODE.SUCCESS : 153 | # Retrieve the left image, depth image in the half-resolution 154 | zed.retrieve_image(image_zed, sl.VIEW.LEFT, sl.MEM.CPU, image_size) 155 | zed.retrieve_image(depth_image_zed, sl.VIEW.DEPTH, sl.MEM.CPU, image_size) 156 | # Retrieve the RGBA point cloud in half resolution 157 | zed.retrieve_measure(point_cloud, sl.MEASURE.XYZRGBA, sl.MEM.CPU, image_size) 158 | 159 | # To recover data from sl.Mat to use it with opencv, use the get_data() method 160 | # It returns a numpy array that can be used as a matrix with opencv 161 | image_ocv = image_zed.get_data() 162 | depth_image_ocv = depth_image_zed.get_data() 163 | 164 | cv2.imshow("Image", image_ocv) 165 | cv2.imshow("Depth", depth_image_ocv) 166 | 167 | key = cv2.waitKey(10) 168 | 169 | process_key_event(zed, key) 170 | 171 | cv2.destroyAllWindows() 172 | zed.close() 173 | 174 | print("\nFINISH") 175 | 176 | if __name__ == "__main__": 177 | main() 178 | -------------------------------------------------------------------------------- /cpp/src/main.cpp: -------------------------------------------------------------------------------- 1 | /////////////////////////////////////////////////////////////////////////// 2 | // 3 | // Copyright (c) 2020, STEREOLABS. 4 | // 5 | // All rights reserved. 6 | // 7 | // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 8 | // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 9 | // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR 10 | // A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT 11 | // OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, 12 | // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT 13 | // LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, 14 | // DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY 15 | // THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 16 | // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 17 | // OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 18 | // 19 | /////////////////////////////////////////////////////////////////////////// 20 | 21 | /*********************************************************************************************** 22 | ** This sample demonstrates how to use the ZED SDK with OpenCV. ** 23 | ** Depth and images are captured with the ZED SDK, converted to OpenCV format and displayed. ** 24 | ***********************************************************************************************/ 25 | 26 | // ZED includes 27 | #include 28 | 29 | // OpenCV includes 30 | #include 31 | // OpenCV dep 32 | 33 | // Not sure this one is necessary. 34 | // #include 35 | 36 | // Sample includes 37 | #include 38 | 39 | using namespace sl; 40 | cv::Mat slMat2cvMat(Mat& input); 41 | #ifdef HAVE_CUDA 42 | cv::cuda::GpuMat slMat2cvMatGPU(Mat& input); 43 | #endif // HAVE_CUDA 44 | 45 | void printHelp(); 46 | 47 | int main(int argc, char **argv) { 48 | 49 | // Create a ZED camera object 50 | Camera zed; 51 | 52 | // Set configuration parameters 53 | InitParameters init_params; 54 | init_params.camera_resolution = RESOLUTION::HD1080; 55 | init_params.depth_mode = DEPTH_MODE::ULTRA; 56 | init_params.coordinate_units = UNIT::METER; 57 | if (argc > 1) init_params.input.setFromSVOFile(argv[1]); 58 | 59 | // Open the camera 60 | ERROR_CODE err = zed.open(init_params); 61 | if (err != ERROR_CODE::SUCCESS) { 62 | printf("%s\n", toString(err).c_str()); 63 | zed.close(); 64 | return 1; // Quit if an error occurred 65 | } 66 | 67 | // Display help in console 68 | printHelp(); 69 | 70 | // Set runtime parameters after opening the camera 71 | RuntimeParameters runtime_parameters; 72 | 73 | // Prepare new image size to retrieve half-resolution images 74 | Resolution image_size = zed.getCameraInformation().camera_configuration.resolution; 75 | int new_width = image_size.width / 2; 76 | int new_height = image_size.height / 2; 77 | 78 | Resolution new_image_size(new_width, new_height); 79 | 80 | // To share data between sl::Mat and cv::Mat, use slMat2cvMat() 81 | // Only the headers and pointer to the sl::Mat are copied, not the data itself 82 | Mat image_zed(new_width, new_height, MAT_TYPE::U8_C4); 83 | cv::Mat image_ocv = slMat2cvMat(image_zed); 84 | 85 | #ifndef HAVE_CUDA // If no cuda, use CPU memory 86 | Mat depth_image_zed(new_width, new_height, MAT_TYPE::U8_C4); 87 | cv::Mat depth_image_ocv = slMat2cvMat(depth_image_zed); 88 | #else 89 | Mat depth_image_zed_gpu(new_width, new_height, MAT_TYPE::U8_C4, sl::MEM::GPU); // alloc sl::Mat to store GPU depth image 90 | cv::cuda::GpuMat depth_image_ocv_gpu = slMat2cvMatGPU(depth_image_zed_gpu); // create an opencv GPU reference of the sl::Mat 91 | cv::Mat depth_image_ocv; // cpu opencv mat for display purposes 92 | #endif 93 | Mat point_cloud; 94 | 95 | // Loop until 'q' is pressed 96 | char key = ' '; 97 | while (key != 'q') { 98 | 99 | if (zed.grab(runtime_parameters) == ERROR_CODE::SUCCESS) { 100 | 101 | // Retrieve the left image, depth image in half-resolution 102 | zed.retrieveImage(image_zed, VIEW::LEFT, MEM::CPU, new_image_size); 103 | #ifndef HAVE_CUDA 104 | // retrieve CPU -> the ocv reference is therefore updated 105 | zed.retrieveImage(depth_image_zed, VIEW::DEPTH, MEM::CPU, new_image_size); 106 | #else 107 | // retrieve GPU -> the ocv reference is therefore updated 108 | zed.retrieveImage(depth_image_zed_gpu, VIEW::DEPTH, MEM::GPU, new_image_size); 109 | #endif 110 | // Retrieve the RGBA point cloud in half-resolution 111 | // To learn how to manipulate and display point clouds, see Depth Sensing sample 112 | zed.retrieveMeasure(point_cloud, MEASURE::XYZRGBA, MEM::CPU, new_image_size); 113 | 114 | // Display image and depth using cv:Mat which share sl:Mat data 115 | cv::imshow("Image", image_ocv); 116 | #ifdef HAVE_CUDA 117 | // download the Ocv GPU data from Device to Host to be displayed 118 | depth_image_ocv_gpu.download(depth_image_ocv); 119 | #endif 120 | cv::imshow("Depth", depth_image_ocv); 121 | 122 | // Handle key event 123 | key = cv::waitKey(10); 124 | processKeyEvent(zed, key); 125 | } 126 | } 127 | 128 | #ifdef HAVE_CUDA 129 | // sl::Mat GPU memory needs to be free before the zed 130 | depth_image_zed_gpu.free(); 131 | #endif 132 | zed.close(); 133 | return 0; 134 | } 135 | 136 | // Mapping between MAT_TYPE and CV_TYPE 137 | int getOCVtype(sl::MAT_TYPE type) { 138 | int cv_type = -1; 139 | switch (type) { 140 | case MAT_TYPE::F32_C1: cv_type = CV_32FC1; break; 141 | case MAT_TYPE::F32_C2: cv_type = CV_32FC2; break; 142 | case MAT_TYPE::F32_C3: cv_type = CV_32FC3; break; 143 | case MAT_TYPE::F32_C4: cv_type = CV_32FC4; break; 144 | case MAT_TYPE::U8_C1: cv_type = CV_8UC1; break; 145 | case MAT_TYPE::U8_C2: cv_type = CV_8UC2; break; 146 | case MAT_TYPE::U8_C3: cv_type = CV_8UC3; break; 147 | case MAT_TYPE::U8_C4: cv_type = CV_8UC4; break; 148 | default: break; 149 | } 150 | return cv_type; 151 | } 152 | 153 | /** 154 | * Conversion function between sl::Mat and cv::Mat 155 | **/ 156 | cv::Mat slMat2cvMat(Mat& input) { 157 | // Since cv::Mat data requires a uchar* pointer, we get the uchar1 pointer from sl::Mat (getPtr()) 158 | // cv::Mat and sl::Mat will share a single memory structure 159 | return cv::Mat(input.getHeight(), input.getWidth(), getOCVtype(input.getDataType()), input.getPtr(MEM::CPU), input.getStepBytes(sl::MEM::CPU)); 160 | } 161 | 162 | #ifdef HAVE_CUDA 163 | /** 164 | * Conversion function between sl::Mat and cv::Mat 165 | **/ 166 | cv::cuda::GpuMat slMat2cvMatGPU(Mat& input) { 167 | // Since cv::Mat data requires a uchar* pointer, we get the uchar1 pointer from sl::Mat (getPtr()) 168 | // cv::Mat and sl::Mat will share a single memory structure 169 | return cv::cuda::GpuMat(input.getHeight(), input.getWidth(), getOCVtype(input.getDataType()), input.getPtr(MEM::GPU), input.getStepBytes(sl::MEM::GPU)); 170 | } 171 | #endif 172 | 173 | /** 174 | * This function displays help in console 175 | **/ 176 | void printHelp() { 177 | std::cout << " Press 's' to save Side by side images" << std::endl; 178 | std::cout << " Press 'p' to save Point Cloud" << std::endl; 179 | std::cout << " Press 'd' to save Depth image" << std::endl; 180 | std::cout << " Press 'm' to switch Point Cloud format" << std::endl; 181 | std::cout << " Press 'n' to switch Depth format" << std::endl; 182 | } 183 | --------------------------------------------------------------------------------