GStreamer Depth Black Screen

Build Information:

-Ubuntu 18.04.6 LTS 

-Nvidia Jetson Xavier NX 

-Jetpack4.6 

-ZED2i Camera 

-ZED SDK 3.6.3 (for Xavier NX) 

Problem 1: I am having problems getting the depth camera stream to display correctly when using zedsrc stream-type:4 (Left_and_Depth_up/down [BGRA] - 8 bits- 4 channels Left and Depth(image)). When running the pipeline, I am receiving a mostly black output with some white streaks which are roughly the hardest/strongest edges in the image (ex: an open door frame). Running the ZED Depth Viewer tool from the SDK on the same system, I get the expected depth image, but not through gstreamer. How can I get the output for the depth stream to display properly through a gstreamer pipeline?

For reference: I am running the following pipeline via the following command line input:

gst-launch-1.0 zedsrc stream-type=4 ! zeddemux name=demux \
 demux.src_left ! queue ! autovideoconvert ! ximagesink \
 demux.src_aux ! queue ! autovideoconvert ! ximagesink

(derived from GStreamer - ZED Demux | Stereolabs)

Problem 2: The goal of the above pipeline was to eventually convert it into c++ code. I have successfully written the c++ app that displays both the left image and the depth map (with the same problems as Problem 1). I was wondering if this was a conversion issue from the sink element so I added a GStreamer probe to the zeddemux’s src_aux pad. (Below, is the gstreamer probe I have added to said pad to read the frame data.) However, the buffer, when read, it only has either a 0 or 1 (probably reflecting the same issue as Problem 1 above which is why I asked this question secondly). I have tried the same probe with zeddemux’s src_left pad and successfully gotten the RGBA values. Thus, my question is:

If I am doing this correctly, how can I obtain a readable depth map from GStreamer? The goal would eventually to be to publish depth data to other applications for specific pixel values.

Probe Function:

static GstPadProbeReturn depth_buffer_probe(GstPad* pad, GstPadProbeInfo* info, gpointer u_data){
    // meta data
    GstBuffer *buf = (GstBuffer*) info->data;
   
 // peeking memory block 0 containing image data
    GstMemory *mem = gst_buffer_peek_memory(buf, 0);

    // getting size of memory block
    long int size = gst_memory_get_sizes(mem, NULL, NULL);

    /*
        getting an image frame that contains the depth map and looking at the
        depth values around the center of the screen
    */
    GstMapInfo inf;
    if(gst_memory_map(mem, &inf, GST_MAP_WRITE)){
        guint16 * ptr = (guint16 *) inf.data; // pointer to the image data
        int width = 1920; // width of the camera image
        int height = 1080; // height of the camera image
        int range = 10; // range of pixels around the preceeding and following the center screen pixel
        int center = (height / 2) * width; // center of the image
        int start = center - range;  
        int end = (center + range);

        /*
         checking the depth value of the pixels around the center of the screen
         within the range [center - range, center + range]
         */
        while(start < end){
            guint16 depth; // depth value at a given pixel
            temp = ptr[start];

            // getting the location of the pixel being looked at and printing this information
            int row = (start / width) % height;
            int col = (start % width);
            std::cout << "row:" << row << ", col: " << col;

            // printing the hexadecimal value of the depth at a given pixel
            printf(", val: %04x\n", depth);
            start++;
        }

        gst_memory_unmap(mem, &inf);
    }

    return GST_PAD_PROBE_OK;
}

The above probe function is set as a callback function with the following code line:

gst_pad_add_probe (zeddemux_srcpad_aux, (GstPadProbeType) \ GST_PAD_PROBE_TYPE_BUFFER), depth_buffer_probe, NULL, NULL);

Update:
Since the time of posting, I have changed the probe to look at the zedsrc src pad instead of the zeddemux src_aux pad and have accessed the image data of the left camera and depth map stored in a GstMapInfo variable retrieved by calling gst_memory_map(). I then looked at the second half of the buffer (first half is the left image and the second half is the depth map). It seems I am getting reasonable depth readings on some pixels but I am still seeing mostly zeroes similar to the problems I am having in the original post. Through outputting the data from the depth map to the screen, I see strong white outlines of important features the camera can see but it is still mostly a black and white image.

Hi @penguin,
what you are reporting about the depth “image” is expected.
The depth information are not good to be directly displayed because the “depth map” contains depth values in 16 bit format with values in the range [0,65535] corresponding to 0 m → 65,535 m.
All the GStreamer sinks display information in 8 bit format with a normalization in the full range, so the final result is not visually significant and all the frames will be essentially black.
If you write your own sink element that retrieves the depth information you will notice that the depth values are correct if associated to real measures in millimeters.
You also correctly notice many zero values, that are relative to not valid depth data, the same as inf or nan in float format.

I add another information for completion.
There is a difference when retrieving the depth map as single stream or as synchronized RGB/Depth stream.
You can compare those two code lines of the zedsrc element to better understand what I mean:

The single stream contains indeed real depth values in mm in 16 bit format, as explained in the post above.
The sync stream instead uses a “trick” to transmit the depth information: the float depth (in millimeters) is casted on 4 unsigned char values. This allows to transmit color values in RGBA format (32bit per pixel) and depth values in float format (32 bit per pixel).

This is the reason why you cannot see a significant depth when displaying the sync stream…

The end goal is to be able to adequately get the depth data for use within our application (without displaying it).

Looking at lines 2025-2038 regarding stream-type 4 (zed-gstreamer/gstzedsrc.cpp at master · stereolabs/zed-gstreamer · GitHub), if I understand correctly, this code snippet describes the copying of the left camera image data into the first half of the data buffer stored within minfo and the depth information/depth map into the second half of the minfo data buffer. I have written a probe function (code below) that probes the zedsrc src pad that reads in this the image data (left image and auxiliary image), as described by the inf (minfo within the zedsrc plugin), and checks out the depth data. However, like we discussed, almost all of this depth map buffer is 0’s. I have checked and roughly 2% of the pixel data is a valid depth data (in mm) and the rest is always 0. The non-0 data corresponds roughly to hard edges in the camera view/image. Do you have any recommendations for zedsrc properties that need to be set or other solutions so that the depth map is filled and not mostly 0? We are ok with <100% fill for the depth map but 2% is not viable for our use.

Code Snippet

static GstPadProbeReturn depth_buffer_probe(GstPad* pad, GstPadProbeInfo* info, gpointer u_data){

  // getting image frame buffer and memory

  GstBuffer *buf = (GstBuffer*) info->data;

  GstMemory *mem = gst_buffer_peek_memory(buf, 0); // peeking memory block 0

  static int count = 0; // how many times zedsrc src pad has had data pass over it

  int validpx = 0;   // number of valid pixels (those with a depth value greater than 0)

  // read depth map on 15th data pass over zedsrc src pad

  if(count == 15){

    if(gst_memory_map(mem, &inf, GST_MAP_WRITE)){

         

      // (hopefully) getting depth data from zedsrc src pad

      uint32_t* depth_ptr = (uint32_t*)(inf.data+inf.size/2);

      int width = 1920; // width of image

      int height = 1080; // height of image

     

      int start = 0;

      int end = inf.size / 8;

      // sending depth frame data to csv

        while(start < end){

            // getting depth value for a given pixel in the depth map

            uint32_t depth_val; // stores depth value

            depth_val = depth_ptr[start];

           

            if(temp != 0)

                validpx++;

            // getting what row and column we are looking at the depth value of

            int row = (start / width) % height;

            int col = (start % width);

            std::cout << "row:" << row << ", col: " << col << ", depth value: " <<   depth_val << std::endl;

            start++;

        }

     

      std::cout << "Number of valid pixels: " << validpx << " out of total pixels (1920*1080): " << 1920*1080 << ", ration: " << ((float)(validpx)/(1920*1080))*100 << "%" << std::endl;

      gst_memory_unmap(mem, &inf);

    }

  }

  count++;

  return GST_PAD_PROBE_OK;

}

int main(){

    /*... gstreamer pipeline code and set up ...*/

    // getting zedsrc source pad

    gchar pad_name_src[16] = "src";

    zedsrc_src_pad = gst_element_get_static_pad(zedsource, pad_name_src);

    // adding probe to

    gst_pad_add_probe (zedsrc_src_pad, (GstPadProbeType) (GST_PAD_PROBE_TYPE_BUFFER), depth_buffer_probe, NULL, NULL);

}

Output From Probe:

"Number of valid pixels: 51137 out of total pixels (1920x1080): 2073600, ratio: 2.4661% 

^Note: This output is roughly consistent across many program executions and the number of valid pixels is calculated by checking the number of pixels whose depth value is greater than 0

The problem is the type of the depth value. It’s not a uint32_t, but a float.
As I wrote in the second post, when you create a pipeline that uses the rgb/depth top/down frame, the depth contains “float” values stored as 4 consecutive unsigned char…
You must perform a cast to float to get the depth value.

I have attempted to do a typecast from uint32_t* (or 4 unsigned char*) to float* as shown in the code below, but I still am receiving zeroes for almost every pixel. Am I typecasting incorrectly?

Code Snippet

static GstPadProbeReturn depth_buffer_probe(GstPad* pad, GstPadProbeInfo* info, gpointer u_data){

  // getting image frame buffer and memory
  GstBuffer *buf = (GstBuffer*) info->data;
  GstMemory *mem = gst_buffer_peek_memory(buf, 0); // peeking memory block 0

  // debug variables
  static int count = 0; // how many times zedsrc src pad has had data pass over it
  int validpx = 0;   // number of valid pixels (those with a depth value greater than 0)

  // read depth map on 15th data pass over zedsrc src pad
  if(count == 15){

    if(gst_memory_map(mem, &inf, GST_MAP_WRITE)){         
      // (hopefully) getting depth data from zedsrc src pad

      float* depth_ptr = (float*)(inf.data+inf.size/2);
      int width = 1920; // width of image
      int height = 1080; // height of image
      int start = 0;
      int end = inf.size / 8;

      // sending depth frame data to csv
        while(start < end){
            // getting depth value for a given pixel in the depth map
            float depth_val; // stores depth value
            depth_val = depth_ptr[start];
           
            if(temp != 0)
                validpx++;

            // getting what row and column we are looking at the depth value of
            int row = (start / width) % height;
            int col = (start % width);
            std::cout << "row:" << row << ", col: " << col << ", depth value: " <<   depth_val << std::endl;
            start++;
        }

      std::cout << "Number of valid pixels: " << validpx << " out of total pixels (1920*1080): " << 1920*1080 << ", ration: " << ((float)(validpx)/(1920*1080))*100 << "%" << std::endl;
      gst_memory_unmap(mem, &inf);
    }
  }

  count++;
  return GST_PAD_PROBE_OK;
}

int main(){

    /*... gstreamer pipeline code and set up ...*/
    // getting zedsrc source pad
    gchar pad_name_src[16] = "src";
    zedsrc_src_pad = gst_element_get_static_pad(zedsource, pad_name_src);

    // adding probe to zedsrc element source pad 
    gst_pad_add_probe (zedsrc_src_pad, (GstPadProbeType) (GST_PAD_PROBE_TYPE_BUFFER), depth_buffer_probe, NULL, NULL);

}

Output From Probe:

"Number of valid pixels: 40149 out of total pixels (1920x1080): 2073600, ratio: 1.93619% 

Hi @penguin
have you solved this problem? What is the camera looking at?

Hi @Myzhar,

I have not solved this problem. Typically I look at a wall and a open doorframe, but the outcome is the same regardless of what I look at. By this, I mean that the depth map is mostly empty (mostly zeroes) whereas if I were to just use the ZED SDK API (v 3.6.4), the depth map is mostly full of accurate values and nonzero values.

Did you see my most recent post regarding float casting and the code I provided? Please let me know if it is what you expected and if you need any more information.

Hi @penguin
first of all please update the SDK to v3.6.5 because if you get the latest Ubuntu update you will face connection issues because of an update to the UVC Kernel Driver.

I can’t find anything wrong with your code, but this part:

if(temp != 0)
    validpx++;

I am running Ubuntu Version 18.04 so I do not believe updating will be beneficial?

In regards to the code line you listed, all that does it check whether a given depth map value is non-zero and if it is, it increases the count of valid pixels for the depth map. This information is printed out at the end. I defined valid pixels this way due to the depth map seemingly being almost all 0’s. Using the ZED SDK API does not produce a mostly empty (mostly 0) depth map whereas the depth map I am grabbing from the ZEDSRC element is. Is this an incorrect way to check?

Besides updating, do you have any other suggestions?

Hi @penguin,
also Ubuntu 18.04 is affected by this issue, when you will update it you will face connection issues.
The important is that you are aware of that.

Regarding temp, I can’t see where it’s updated and declared.

I’m going to debug the zedsrc element to be sure that the stored depth information is correct.

I verified that the zedsrc element works correctly.
The “conversion” code is correct:

I verified it by using the zeddemux element:

Hi @penguin
I found a bug in the zedsrc element.
For some reason, the texture confidence threshold is forced to 0 in runtime and the resulting depth map is so sparse… not a data type conversion problem.
I’m fixing it.

2 Likes

Hi @Myzhar

Is this issue resolved, since I am also trying to access the depth data from the zed src but we are also facing similar issues.

Yes, solved a long time ago