├── .github ├── ISSUE_TEMPLATE │ ├── 1_feature_request.yml │ ├── 2_bug_report.yml │ └── config.yml └── workflows │ └── stale_issues.yml ├── README.md ├── cpp ├── CMakeLists.txt ├── README.md └── src │ └── main.cpp └── python └── multi_camera.py /.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 | -------------------------------------------------------------------------------- /.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 | -------------------------------------------------------------------------------- /.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 | -------------------------------------------------------------------------------- /.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 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # Stereolabs ZED - Using multiple ZED 2 | 3 | This sample shows how to use multiple ZED cameras in a single application. 4 | 5 | ## Getting started 6 | 7 | - First, download the latest version of the ZED SDK on [stereolabs.com](https://www.stereolabs.com). 8 | - 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) 9 | 10 | ### Prerequisites 11 | 12 | - Windows 10, Ubuntu LTS 13 | - [ZED SDK](https://www.stereolabs.com/developers/) and its dependencies ([CUDA](https://developer.nvidia.com/cuda-downloads), [OpenCV](https://github.com/opencv/opencv/releases)) 14 | 15 | ## How it works 16 | 17 | - Video capture for each camera is done in a separate thread for optimal performance. You can specify the number of ZED used by changing the `NUM_CAMERAS` parameter. 18 | - Each camera has its own timestamp (uncomment a line to display it). These timestamps can be used for device synchronization. 19 | - OpenCV is used to display the images and depth maps. To stop the application, simply press 'q'. 20 | 21 | ### Limitations 22 | 23 | - This sample works on Windows with the latest firmware v.1523 24 | - USB bandwidth: The ZED in 1080p30 mode generates around 250MB/s of image data. USB 3.0 maximum bandwidth is around 400MB/s, so the number of cameras, resolutions and framerates you can use on a single machine will be limited by the USB 3.0 controller on the motherboard. When bandwidth limit is exceeded, corrupted frames (green or purple frames, tearing) can appear. 25 | - Using a single USB 3.0 controller, here are configurations that we tested: 26 | - 2 ZEDs in HD1080 @ 15fps and HD720 @ 30fps 27 | - 3 ZEDs in HD720 @ 15fps 28 | - 4 ZEDs in VGA @ 30fps 29 | - To use multiple ZED at full speed on a single computer, we recommend adding USB3.0 PCIe expansion cards. 30 | - You can also use multiple GPUs to load-balance computations (use `param.device` to select a GPU for a ZED) and improve performance. 31 | 32 | ## Support 33 | If you need assistance go to our Community site at https://community.stereolabs.com/ 34 | -------------------------------------------------------------------------------- /cpp/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | CMAKE_MINIMUM_REQUIRED(VERSION 2.4) 2 | PROJECT(ZED_Multi_Camera) 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 | IF(NOT MSVC) 18 | SET(SPECIAL_OS_LIBS "pthread" "X11") 19 | ENDIF() 20 | 21 | find_package(ZED 3 REQUIRED) 22 | find_package(OpenCV REQUIRED) 23 | find_package(CUDA ${ZED_CUDA_VERSION} REQUIRED) 24 | 25 | include_directories(${CUDA_INCLUDE_DIRS}) 26 | include_directories(${ZED_INCLUDE_DIRS}) 27 | include_directories(${OpenCV_INCLUDE_DIRS}) 28 | 29 | link_directories(${ZED_LIBRARY_DIR}) 30 | link_directories(${OpenCV_LIBRARY_DIRS}) 31 | link_directories(${CUDA_LIBRARY_DIRS}) 32 | 33 | ADD_EXECUTABLE(${PROJECT_NAME} src/main.cpp) 34 | add_definitions(-std=c++14 -O3) 35 | 36 | if (LINK_SHARED_ZED) 37 | SET(ZED_LIBS ${ZED_LIBRARIES} ${CUDA_CUDA_LIBRARY} ${CUDA_CUDART_LIBRARY} ${SPECIAL_OS_LIBS}) 38 | else() 39 | SET(ZED_LIBS ${ZED_STATIC_LIBRARIES} ${CUDA_CUDA_LIBRARY} ${CUDA_LIBRARY} ${SPECIAL_OS_LIBS}) 40 | endif() 41 | 42 | TARGET_LINK_LIBRARIES(${PROJECT_NAME} ${ZED_LIBS} ${SPECIAL_OS_LIBS} ${OpenCV_LIBRARIES}) 43 | -------------------------------------------------------------------------------- /cpp/README.md: -------------------------------------------------------------------------------- 1 | # Stereolabs ZED - Using multiple ZED 2 | 3 | This sample shows how to use multiple ZED cameras in a single application. 4 | 5 | ## Getting started 6 | 7 | - First, download the latest version of the ZED SDK on [stereolabs.com](https://www.stereolabs.com). 8 | - For more information, read the ZED [API documentation](https://www.stereolabs.com/developers/documentation/API/latest). 9 | 10 | ### Prerequisites 11 | 12 | - Windows 10, Ubuntu LTS 13 | - [ZED SDK](https://www.stereolabs.com/developers/) and its dependencies ([CUDA](https://developer.nvidia.com/cuda-downloads), [OpenCV](https://github.com/opencv/opencv/releases)) 14 | 15 | ## Build the program 16 | 17 | Download the sample and follow these instructions: 18 | 19 | #### Build for Windows 20 | 21 | - Create a folder called "build" in the source folder 22 | - Open cmake-gui and select the source and build folders 23 | - Generate the Visual Studio `Win64` solution 24 | - Open the resulting solution and change the solution configuration to `Release` 25 | - Build solution 26 | 27 | #### Build for Linux 28 | 29 | Open a terminal in the sample directory and execute the following command: 30 | 31 | mkdir build 32 | cd build 33 | cmake .. 34 | make 35 | 36 | ## Run the program 37 | 38 | - Navigate to the build directory and launch the executable file 39 | - Or open a terminal in the build directory and run the sample : 40 | 41 | ./ZED\ Multi\ Camera 42 | 43 | ## How it works 44 | 45 | - Video capture for each camera is done in a separate thread for optimal performance. You can specify the number of ZED used by changing the `NUM_CAMERAS` parameter. 46 | - Each camera has its own timestamp (uncomment a line to display it). These timestamps can be used for device synchronization. 47 | - OpenCV is used to display the images and depth maps. To stop the application, simply press 'q'. 48 | 49 | 50 | ### Limitations 51 | 52 | - This sample works on Windows with the latest firmware v.1523 53 | - USB bandwidth: The ZED in 1080p30 mode generates around 250MB/s of image data. USB 3.0 maximum bandwidth is around 400MB/s, so the number of cameras, resolutions and framerates you can use on a single machine will be limited by the USB 3.0 controller on the motherboard. When bandwidth limit is exceeded, corrupted frames (green or purple frames, tearing) can appear. 54 | - Using a single USB 3.0 controller, here are configurations that we tested: 55 | - 2 ZEDs in HD1080 @ 15fps and HD720 @ 30fps 56 | - 3 ZEDs in HD720 @ 15fps 57 | - 4 ZEDs in VGA @ 30fps 58 | - To use multiple ZED at full speed on a single computer, we recommend adding USB3.0 PCIe expansion cards. 59 | - You can also use multiple GPUs to load-balance computations (use `param.device` to select a GPU for a ZED) and improve performance. 60 | -------------------------------------------------------------------------------- /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 | /****************************************************************************************************************** 23 | ** This sample demonstrates how to use two ZEDs with the ZED SDK, each grab are in a separate thread ** 24 | ** This sample has been tested with 3 ZEDs in HD720@30fps resolution. Linux only. ** 25 | *******************************************************************************************************************/ 26 | 27 | #include 28 | 29 | #include 30 | // Using std and sl namespaces 31 | using namespace std; 32 | using namespace sl; 33 | 34 | void zed_acquisition(Camera& zed, cv::Mat& image_low_res, bool& run, Timestamp& ts); 35 | 36 | int main(int argc, char** argv) { 37 | 38 | InitParameters init_parameters; 39 | init_parameters.depth_mode = DEPTH_MODE::PERFORMANCE; 40 | init_parameters.camera_resolution = RESOLUTION::HD720; 41 | 42 | vector< DeviceProperties> devList = Camera::getDeviceList(); 43 | int nb_detected_zed = devList.size(); 44 | 45 | for (int z = 0; z < nb_detected_zed; z++) { 46 | std::cout << "ID : " << devList[z].id << " ,model : " << devList[z].camera_model << " , S/N : " << devList[z].serial_number << " , state : "< zeds(nb_detected_zed); 57 | // try to open every detected cameras 58 | for (int z = 0; z < nb_detected_zed; z++) { 59 | init_parameters.input.setFromCameraID(z); 60 | ERROR_CODE err = zeds[z].open(init_parameters); 61 | if (err == ERROR_CODE::SUCCESS) { 62 | auto cam_info = zeds[z].getCameraInformation(); 63 | cout << cam_info.camera_model << ", ID: " << z << ", SN: " << cam_info.serial_number << " Opened" << endl; 64 | } else { 65 | cout << "ZED ID:" << z << " Error: " << err << endl; 66 | zeds[z].close(); 67 | } 68 | } 69 | 70 | bool run = true; 71 | // Create a grab thread for each opened camera 72 | vector thread_pool(nb_detected_zed); // compute threads 73 | vector images_lr(nb_detected_zed); // display images 74 | vector wnd_names(nb_detected_zed); // display windows names 75 | vector images_ts(nb_detected_zed); // images timestamps 76 | 77 | for (int z = 0; z < nb_detected_zed; z++) 78 | if (zeds[z].isOpened()) { 79 | // create an image to store Left+Depth image 80 | images_lr[z] = cv::Mat(404, 720*2, CV_8UC4); 81 | // camera acquisition thread 82 | thread_pool[z] = std::thread(zed_acquisition, ref(zeds[z]), ref(images_lr[z]), ref(run), ref(images_ts[z])); 83 | // create windows for display 84 | wnd_names[z] = "ZED ID: " + to_string(z); 85 | cv::namedWindow(wnd_names[z]); 86 | } 87 | 88 | vector last_ts(nb_detected_zed, 0); // use to detect new images 89 | 90 | char key = ' '; 91 | // Loop until 'Esc' is pressed 92 | while (key != 27) { 93 | // Resize and show images 94 | for (int z = 0; z < nb_detected_zed; z++) { 95 | if (images_ts[z] > last_ts[z]) { // if the current timestamp is newer it is a new image 96 | cv::imshow(wnd_names[z], images_lr[z]); 97 | last_ts[z] = images_ts[z]; 98 | } 99 | } 100 | 101 | key = cv::waitKey(10); 102 | } 103 | 104 | // stop all running threads 105 | run = false; 106 | 107 | // Wait for every thread to be stopped 108 | for (int z = 0; z < nb_detected_zed; z++) 109 | if (zeds[z].isOpened()) 110 | thread_pool[z].join(); 111 | 112 | return EXIT_SUCCESS; 113 | } 114 | 115 | void zed_acquisition(Camera& zed, cv::Mat& image_low_res, bool& run, Timestamp& ts) { 116 | Mat zed_image; 117 | const int w_low_res = image_low_res.cols / 2; 118 | const int h_low_res = image_low_res.rows; 119 | Resolution low_res(w_low_res, h_low_res); 120 | while (run) { 121 | // grab current images and compute depth 122 | if (zed.grab() == ERROR_CODE::SUCCESS) { 123 | zed.retrieveImage(zed_image, VIEW::LEFT, MEM::CPU, low_res); 124 | // copy Left image to the left part of the side by side image 125 | cv::Mat(h_low_res, w_low_res, CV_8UC4, zed_image.getPtr(MEM::CPU)).copyTo(image_low_res(cv::Rect(0, 0, w_low_res, h_low_res))); 126 | zed.retrieveImage(zed_image, VIEW::DEPTH, MEM::CPU, low_res); 127 | // copy Dpeth image to the right part of the side by side image 128 | cv::Mat(h_low_res, w_low_res, CV_8UC4, zed_image.getPtr(MEM::CPU)).copyTo(image_low_res(cv::Rect(w_low_res, 0, w_low_res, h_low_res))); 129 | ts = zed.getTimestamp(TIME_REFERENCE::IMAGE); 130 | } 131 | sleep_ms(2); 132 | } 133 | zed.close(); 134 | } 135 | -------------------------------------------------------------------------------- /python/multi_camera.py: -------------------------------------------------------------------------------- 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 | Multi cameras sample showing how to open multiple ZED in one program 23 | """ 24 | 25 | import pyzed.sl as sl 26 | import cv2 27 | import numpy as np 28 | import threading 29 | import time 30 | import signal 31 | 32 | zed_list = [] 33 | left_list = [] 34 | depth_list = [] 35 | timestamp_list = [] 36 | thread_list = [] 37 | stop_signal = False 38 | 39 | def signal_handler(signal, frame): 40 | global stop_signal 41 | stop_signal=True 42 | time.sleep(0.5) 43 | exit() 44 | 45 | def grab_run(index): 46 | global stop_signal 47 | global zed_list 48 | global timestamp_list 49 | global left_list 50 | global depth_list 51 | 52 | runtime = sl.RuntimeParameters() 53 | while not stop_signal: 54 | err = zed_list[index].grab(runtime) 55 | if err == sl.ERROR_CODE.SUCCESS: 56 | zed_list[index].retrieve_image(left_list[index], sl.VIEW.LEFT) 57 | zed_list[index].retrieve_measure(depth_list[index], sl.MEASURE.DEPTH) 58 | timestamp_list[index] = zed_list[index].get_timestamp(sl.TIME_REFERENCE.CURRENT).data_ns 59 | time.sleep(0.001) #1ms 60 | zed_list[index].close() 61 | 62 | def main(): 63 | global stop_signal 64 | global zed_list 65 | global left_list 66 | global depth_list 67 | global timestamp_list 68 | global thread_list 69 | signal.signal(signal.SIGINT, signal_handler) 70 | 71 | print("Running...") 72 | init = sl.InitParameters() 73 | init.camera_resolution = sl.RESOLUTION.HD720 74 | init.camera_fps = 30 # The framerate is lowered to avoid any USB3 bandwidth issues 75 | 76 | #List and open cameras 77 | name_list = [] 78 | last_ts_list = [] 79 | cameras = sl.Camera.get_device_list() 80 | index = 0 81 | for cam in cameras: 82 | init.set_from_serial_number(cam.serial_number) 83 | name_list.append("ZED {}".format(cam.serial_number)) 84 | print("Opening {}".format(name_list[index])) 85 | zed_list.append(sl.Camera()) 86 | left_list.append(sl.Mat()) 87 | depth_list.append(sl.Mat()) 88 | timestamp_list.append(0) 89 | last_ts_list.append(0) 90 | status = zed_list[index].open(init) 91 | if status != sl.ERROR_CODE.SUCCESS: 92 | print(repr(status)) 93 | zed_list[index].close() 94 | index = index +1 95 | 96 | #Start camera threads 97 | for index in range(0, len(zed_list)): 98 | if zed_list[index].is_opened(): 99 | thread_list.append(threading.Thread(target=grab_run, args=(index,))) 100 | thread_list[index].start() 101 | 102 | #Display camera images 103 | key = '' 104 | while key != 113: # for 'q' key 105 | for index in range(0, len(zed_list)): 106 | if zed_list[index].is_opened(): 107 | if (timestamp_list[index] > last_ts_list[index]): 108 | cv2.imshow(name_list[index], left_list[index].get_data()) 109 | x = round(depth_list[index].get_width() / 2) 110 | y = round(depth_list[index].get_height() / 2) 111 | err, depth_value = depth_list[index].get_value(x, y) 112 | if np.isfinite(depth_value): 113 | print("{} depth at center: {}MM".format(name_list[index], round(depth_value))) 114 | last_ts_list[index] = timestamp_list[index] 115 | key = cv2.waitKey(10) 116 | cv2.destroyAllWindows() 117 | 118 | #Stop the threads 119 | stop_signal = True 120 | for index in range(0, len(thread_list)): 121 | thread_list[index].join() 122 | 123 | print("\nFINISH") 124 | 125 | if __name__ == "__main__": 126 | main() 127 | --------------------------------------------------------------------------------