Skip to content

Commit 2ab7758

Browse files
authored
Merge pull request #66 from stereolabs/fix_zedsrc_resolution
Fix zedsrc resolution
2 parents 75c2fed + 0cd2b1d commit 2ab7758

File tree

2 files changed

+54
-12
lines changed

2 files changed

+54
-12
lines changed

README.md

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -136,6 +136,9 @@ Most of the properties follow the same name as the C++ API. Except that `_` is r
136136
area-file-path : Area localization file that describes the surroundings, saved from a previous tracking session.
137137
flags: readable, writable
138138
String. Default: ""
139+
blocksize : Size in bytes to read per buffer (-1 = default)
140+
flags: readable, writable
141+
Unsigned Integer. Range: 0 - 4294967295 Default: 4096
139142
bt-allow-red-prec : Set to TRUE to enable Body Tracking reduced inference precision
140143
flags: readable, writable
141144
Boolean. Default: false
@@ -197,10 +200,10 @@ Most of the properties follow the same name as the C++ API. Except that `_` is r
197200
(2): Auto - Auto mode (ZED2/ZED2i/ZED-M only)
198201
camera-resolution : Camera Resolution
199202
flags: readable, writable
200-
Enum "GstZedsrcResolution" Default: 6, "Default value for the camera model"
203+
Enum "GstZedSrcRes" Default: 6, "Default value for the camera model"
201204
(0): HD2K (USB3) - 2208x1242
202-
(2): HD1200 (GMSL2) - 1920x1200
203205
(1): HD1080 (USB3/GMSL2) - 1920x1080
206+
(2): HD1200 (GMSL2) - 1920x1200
204207
(3): HD720 (USB3) - 1280x720
205208
(4): SVGA (GMSL2) - 960x600
206209
(5): VGA (USB3) - 672x376
@@ -398,6 +401,9 @@ Most of the properties follow the same name as the C++ API. Except that `_` is r
398401
od-prediction-timeout-s: Object prediction timeout (sec)
399402
flags: readable, writable
400403
Float. Range: 0 - 1 Default: 0.2
404+
opencv-calibration-file: Optional OpenCV Calibration File
405+
flags: readable, writable
406+
String. Default: ""
401407
parent : The parent of the object
402408
flags: readable, writable, 0x2000
403409
Object of type "GstObject"

gst-zed-src/gstzedsrc.cpp

Lines changed: 46 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -146,6 +146,16 @@ enum {
146146
N_PROPERTIES
147147
};
148148

149+
typedef enum {
150+
GST_ZEDSRC_HD2K = 0, // 2208x1242
151+
GST_ZEDSRC_HD1080 = 1, // 1920x1080
152+
GST_ZEDSRC_HD1200 = 2, // 1920x1200
153+
GST_ZEDSRC_HD720 = 3, // 1280x720
154+
GST_ZEDSRC_SVGA = 4, // 960x600
155+
GST_ZEDSRC_VGA = 5, // 672x376
156+
GST_ZEDSRC_AUTO_RES = 6, // Default value for the camera model
157+
} GstZedSrcRes;
158+
149159
typedef enum {
150160
GST_ZEDSRC_120FPS = 120,
151161
GST_ZEDSRC_100FPS = 100,
@@ -220,7 +230,7 @@ typedef enum {
220230
/////////////////////////////////////////////////////////////////////////////
221231

222232
// INITIALIZATION
223-
#define DEFAULT_PROP_CAM_RES static_cast<gint>(sl::RESOLUTION::AUTO)
233+
#define DEFAULT_PROP_CAM_RES GST_ZEDSRC_AUTO_RES
224234
#define DEFAULT_PROP_CAM_FPS GST_ZEDSRC_15FPS
225235
#define DEFAULT_PROP_SDK_VERBOSE 0
226236
#define DEFAULT_PROP_CAM_FLIP 2
@@ -364,18 +374,18 @@ static GType gst_zedsrc_resol_get_type(void) {
364374

365375
if (!zedsrc_resol_type) {
366376
static GEnumValue pattern_types[] = {
367-
{static_cast<gint>(sl::RESOLUTION::HD2K), "2208x1242", "HD2K (USB3)"},
368-
{static_cast<gint>(sl::RESOLUTION::HD1200), "1920x1200", "HD1200 (GMSL2)"},
369-
{static_cast<gint>(sl::RESOLUTION::HD1080), "1920x1080", "HD1080 (USB3/GMSL2)"},
370-
{static_cast<gint>(sl::RESOLUTION::HD720), "1280x720", "HD720 (USB3)"},
371-
{static_cast<gint>(sl::RESOLUTION::SVGA), "960x600", "SVGA (GMSL2)"},
372-
{static_cast<gint>(sl::RESOLUTION::VGA), "672x376", "VGA (USB3)"},
373-
{static_cast<gint>(sl::RESOLUTION::AUTO), "Automatic",
377+
{GST_ZEDSRC_HD2K, "2208x1242", "HD2K (USB3)"},
378+
{GST_ZEDSRC_HD1080, "1920x1080", "HD1080 (USB3/GMSL2)"},
379+
{GST_ZEDSRC_HD1200, "1920x1200", "HD1200 (GMSL2)"},
380+
{GST_ZEDSRC_HD720, "1280x720", "HD720 (USB3)"},
381+
{GST_ZEDSRC_SVGA, "960x600", "SVGA (GMSL2)"},
382+
{GST_ZEDSRC_VGA, "672x376", "VGA (USB3)"},
383+
{GST_ZEDSRC_AUTO_RES, "Automatic",
374384
"Default value for the camera model"},
375385
{0, NULL, NULL},
376386
};
377387

378-
zedsrc_resol_type = g_enum_register_static("GstZedsrcResolution", pattern_types);
388+
zedsrc_resol_type = g_enum_register_static("GstZedSrcRes", pattern_types);
379389
}
380390

381391
return zedsrc_resol_type;
@@ -2181,7 +2191,33 @@ static gboolean gst_zedsrc_start(GstBaseSrc *bsrc) {
21812191

21822192
GST_INFO("CAMERA INITIALIZATION PARAMETERS");
21832193

2184-
init_params.camera_resolution = static_cast<sl::RESOLUTION>(src->camera_resolution);
2194+
switch(src->camera_resolution) {
2195+
case GST_ZEDSRC_HD2K:
2196+
init_params.camera_resolution = sl::RESOLUTION::HD2K;
2197+
break;
2198+
case GST_ZEDSRC_HD1080:
2199+
init_params.camera_resolution = sl::RESOLUTION::HD1080;
2200+
break;
2201+
case GST_ZEDSRC_HD1200:
2202+
init_params.camera_resolution = sl::RESOLUTION::HD1200;
2203+
break;
2204+
case GST_ZEDSRC_HD720:
2205+
init_params.camera_resolution = sl::RESOLUTION::HD720;
2206+
break;
2207+
case GST_ZEDSRC_SVGA:
2208+
init_params.camera_resolution = sl::RESOLUTION::SVGA;
2209+
break;
2210+
case GST_ZEDSRC_VGA:
2211+
init_params.camera_resolution = sl::RESOLUTION::SVGA;
2212+
break;
2213+
case GST_ZEDSRC_AUTO_RES:
2214+
init_params.camera_resolution = sl::RESOLUTION::AUTO;
2215+
break;
2216+
default:
2217+
GST_ELEMENT_ERROR(src, RESOURCE, NOT_FOUND,
2218+
("Failed to set camera resolution"), (NULL));
2219+
return FALSE;
2220+
}
21852221
GST_INFO(" * Camera resolution: %s", sl::toString(init_params.camera_resolution).c_str());
21862222
init_params.camera_fps = src->camera_fps;
21872223
GST_INFO(" * Camera FPS: %d", init_params.camera_fps);

0 commit comments

Comments
 (0)