Skip to content

Commit a9ee14b

Browse files
authored
Merge pull request #38 from stereolabs/devel
Devel
2 parents 85924d6 + 6164bc9 commit a9ee14b

File tree

5 files changed

+46
-21
lines changed

5 files changed

+46
-21
lines changed

README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -38,7 +38,7 @@ GStreamer plugin package for ZED Cameras. The package is composed of several plu
3838

3939
### Windows installation
4040

41-
* Install the latest ZED SDK v3.5.x from the [official download page](https://www.stereolabs.com/developers/release/) [Optional to compile the `zedsrc` plugin to acquire data from a ZED camera device]
41+
* Install the latest ZED SDK v3.7.x from the [official download page](https://www.stereolabs.com/developers/release/) [Optional to compile the `zedsrc` plugin to acquire data from a ZED camera device]
4242
* Install [Git](https://git-scm.com/) or download a ZIP archive
4343
* Install [CMake](https://cmake.org/)
4444
* Install a [GStreamer distribution (**both `runtime` and `development` installers**)](https://gstreamer.freedesktop.org/download/).

gst-zed-demux/gstzeddemux.cpp

+6-1
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,8 @@
2727
#include "gstzeddemux.h"
2828
#include "gst-zed-meta/gstzedmeta.h"
2929

30+
#include <stdio.h>
31+
3032
GST_DEBUG_CATEGORY_STATIC (gst_zeddemux_debug);
3133
#define GST_CAT_DEFAULT gst_zeddemux_debug
3234

@@ -633,7 +635,10 @@ static GstFlowReturn gst_zeddemux_chain(GstPad* pad, GstObject * parent, GstBuff
633635

634636
for (unsigned long i = 0; i < map_out_aux.size/(sizeof(guint16)); i++)
635637
{
636-
*(gst_out_data++) = static_cast<guint16>(*(gst_in_data++));
638+
float depth = static_cast<float>(*(gst_in_data++));
639+
*(gst_out_data++) = static_cast<guint16>(depth);
640+
641+
//printf( "#%lu: %g / %u %u \n", i, depth, *(gst_out_data-1), *(gst_in_data-1));
637642
}
638643
}
639644

gst-zed-src/gstzedsrc.cpp

+37-15
Original file line numberDiff line numberDiff line change
@@ -178,7 +178,7 @@ typedef enum {
178178
//#define DEFAULT_PROP_RIGHT_DEPTH FALSE
179179

180180
// RUNTIME
181-
#define DEFAULT_PROP_CONFIDENCE_THRESH 80
181+
#define DEFAULT_PROP_CONFIDENCE_THRESH 50
182182
#define DEFAULT_PROP_TEXTURE_CONF_THRESH 100
183183
#define DEFAULT_PROP_3D_REF_FRAME static_cast<gint>(sl::REFERENCE_FRAME::WORLD)
184184
#define DEFAULT_PROP_SENSING_MODE static_cast<gint>(sl::SENSING_MODE::STANDARD)
@@ -447,6 +447,9 @@ static GType gst_zedsrc_depth_mode_get_type (void)
447447

448448
if (!zedsrc_depth_mode_type) {
449449
static GEnumValue pattern_types[] = {
450+
{ static_cast<gint>(sl::DEPTH_MODE::NEURAL),
451+
"End to End Neural disparity estimation, requires AI module",
452+
"NEURAL" },
450453
{ static_cast<gint>(sl::DEPTH_MODE::ULTRA),
451454
"Computation mode favorising edges and sharpness. Requires more GPU memory and computation power.",
452455
"ULTRA" },
@@ -1732,27 +1735,23 @@ static gboolean gst_zedsrc_start( GstBaseSrc * bsrc )
17321735
GST_INFO(" * LED_STATUS: %s", (src->led_status?"ON":"OFF"));
17331736
// <---- Camera Controls
17341737

1735-
// ----> Set runtime parameters
1738+
// ----> Runtime parameters
17361739
GST_INFO("CAMERA RUNTIME PARAMETERS");
17371740
if( src->depth_mode==static_cast<gint>(sl::DEPTH_MODE::NONE)
17381741
&& !src->pos_tracking)
17391742
{
1740-
src->zedRtParams.enable_depth = false;
1743+
GST_INFO(" * Depth calculation: ON" );
17411744
}
17421745
else
17431746
{
1744-
src->zedRtParams.enable_depth = true;
1747+
GST_INFO(" * Depth calculation: OFF" );
17451748
}
1746-
GST_INFO(" * Depth calculation: %s", (src->zedRtParams.enable_depth?"ON":"OFF"));
1747-
src->zedRtParams.confidence_threshold = src->confidence_threshold;
1748-
GST_INFO(" * Depth Confidence threshold: %d", src->zedRtParams.confidence_threshold);
1749-
src->zedRtParams.texture_confidence_threshold = src->texture_confidence_threshold;
1750-
GST_INFO(" * Depth Texture Confidence threshold: %d", src->zedRtParams.texture_confidence_threshold );
1751-
src->zedRtParams.measure3D_reference_frame = static_cast<sl::REFERENCE_FRAME>(src->measure3D_reference_frame);
1752-
GST_INFO(" * 3D Reference Frame: %s", sl::toString(src->zedRtParams.measure3D_reference_frame).c_str());
1753-
src->zedRtParams.sensing_mode = static_cast<sl::SENSING_MODE>(src->sensing_mode);
1754-
GST_INFO(" * Sensing Mode: %s", sl::toString(src->zedRtParams.sensing_mode).c_str());
1755-
// <---- Set runtime parameters
1749+
1750+
GST_INFO(" * Depth Confidence threshold: %d", src->confidence_threshold);
1751+
GST_INFO(" * Depth Texture Confidence threshold: %d", src->texture_confidence_threshold );
1752+
GST_INFO(" * 3D Reference Frame: %s", sl::toString((sl::COORDINATE_SYSTEM)src->measure3D_reference_frame).c_str());
1753+
GST_INFO(" * Sensing Mode: %s", sl::toString((sl::SENSING_MODE)src->sensing_mode).c_str());
1754+
// <---- Runtime parameters
17561755

17571756
// ----> Positional tracking
17581757
GST_INFO("POSITIONAL TRACKING PARAMETERS");
@@ -1931,8 +1930,27 @@ static GstFlowReturn gst_zedsrc_fill( GstPushSrc * psrc, GstBuffer * buf )
19311930
src->is_started = TRUE;
19321931
}
19331932

1933+
// ----> Set runtime parameters
1934+
sl::RuntimeParameters zedRtParams; // runtime parameters
1935+
1936+
GST_INFO("CAMERA RUNTIME PARAMETERS");
1937+
if( src->depth_mode==static_cast<gint>(sl::DEPTH_MODE::NONE) && !src->pos_tracking)
1938+
{
1939+
zedRtParams.enable_depth = false;
1940+
}
1941+
else
1942+
{
1943+
zedRtParams.enable_depth = true;
1944+
}
1945+
zedRtParams.confidence_threshold = src->confidence_threshold;
1946+
zedRtParams.texture_confidence_threshold = src->texture_confidence_threshold;
1947+
zedRtParams.measure3D_reference_frame = static_cast<sl::REFERENCE_FRAME>(src->measure3D_reference_frame);
1948+
zedRtParams.sensing_mode = static_cast<sl::SENSING_MODE>(src->sensing_mode);
1949+
zedRtParams.remove_saturated_areas = true;
1950+
// <---- Set runtime parameters
1951+
19341952
// ----> ZED grab
1935-
ret = src->zed.grab(src->zedRtParams);
1953+
ret = src->zed.grab(zedRtParams);
19361954

19371955
if( ret!=sl::ERROR_CODE::SUCCESS )
19381956
{
@@ -1981,12 +1999,14 @@ static GstFlowReturn gst_zedsrc_fill( GstPushSrc * psrc, GstBuffer * buf )
19811999
ret = src->zed.retrieveMeasure(depth_data, sl::MEASURE::DEPTH, sl::MEM::CPU );
19822000
#else
19832001
ret = src->zed.retrieveMeasure(depth_data, sl::MEASURE::DEPTH_U16_MM, sl::MEM::CPU );
2002+
//depth_data.write( "test_depth_16.png" );
19842003
#endif
19852004
}
19862005
else if(src->stream_type== GST_ZEDSRC_LEFT_DEPTH)
19872006
{
19882007
ret = src->zed.retrieveImage(left_img, sl::VIEW::LEFT, sl::MEM::CPU );
19892008
ret = src->zed.retrieveMeasure(depth_data, sl::MEASURE::DEPTH, sl::MEM::CPU );
2009+
//depth_data.write( "test_depth_32.png" );
19902010
}
19912011

19922012
if( ret!=sl::ERROR_CODE::SUCCESS )
@@ -2034,6 +2054,8 @@ static GstFlowReturn gst_zedsrc_fill( GstPushSrc * psrc, GstBuffer * buf )
20342054

20352055
for (unsigned long i = 0; i < minfo.size/8; i++) {
20362056
*(gst_data++) = static_cast<uint32_t>(*(depthDataPtr++));
2057+
2058+
//printf( "#%lu: %u / %g %u \n", i, *(gst_data-1), *(depthDataPtr-1), static_cast<uint32_t>(*(depthDataPtr-1)));
20372059
}
20382060
}
20392061
else

gst-zed-src/gstzedsrc.h

+1-3
Original file line numberDiff line numberDiff line change
@@ -43,7 +43,7 @@ struct _GstZedSrc
4343

4444
// ZED camera object
4545
sl::Camera zed;
46-
sl::RuntimeParameters zedRtParams; // runtime parameters
46+
4747

4848
gboolean is_started; // grab started flag
4949

@@ -111,8 +111,6 @@ struct _GstZedSrc
111111
gint whitebalance_temperature;
112112
gboolean whitebalance_temperature_auto;
113113
gboolean led_status;
114-
115-
116114
// <---- Properties
117115

118116
GstClockTime acq_start_time;

scripts/linux/simple-depth-fps_rendering.sh

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,4 +2,4 @@
22

33
# Example pipeline to acquire a depth stream and render it dispaying the current FPS using default values for each parameter
44

5-
gst-launch-1.0 zedsrc stream-type=3 ! queue ! autovideoconvert ! queue ! fpsdisplaysink
5+
gst-launch-1.0 zedsrc stream-type=3 depth-mode=4 ! queue ! autovideoconvert ! queue ! fpsdisplaysink

0 commit comments

Comments
 (0)