Skip to content

Commit 053fd0f

Browse files
committed
Improvements from ZED SDK 4.1.3
1 parent 7dcca1a commit 053fd0f

File tree

2 files changed

+19
-3
lines changed

2 files changed

+19
-3
lines changed

src/pyzed/sl.pyx

Lines changed: 16 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -282,13 +282,19 @@ class ERROR_CODE(enum.Enum):
282282
# | ZED2i | ZED 2i camera model |
283283
# | ZED_X | ZED X camera model |
284284
# | ZED_XM | ZED X Mini (ZED XM) camera model |
285+
# | VIRTUAL_ZED_X | Virtual ZED-X generated from 2 ZED-XOne |
286+
# | ZED_XONE_GS | ZED XOne with global shutter AR0234 sensor |
287+
# | ZED_XONE_UHD | ZED XOne with 4K rolling shutter IMX678 sensor |
285288
class MODEL(enum.Enum):
286289
ZED = <int>c_MODEL.ZED
287290
ZED_M = <int>c_MODEL.ZED_M
288291
ZED2 = <int>c_MODEL.ZED2
289292
ZED2i = <int>c_MODEL.ZED2i
290293
ZED_X = <int>c_MODEL.ZED_X
291294
ZED_XM = <int>c_MODEL.ZED_XM
295+
VIRTUAL_ZED_X = <int>c_MODEL.VIRTUAL_ZED_X
296+
ZED_XONE_GS = <int>c_MODEL.ZED_XONE_GS
297+
ZED_XONE_UHD = <int>c_MODEL.ZED_XONE_UHD
292298
LAST = <int>c_MODEL.MODEL_LAST
293299

294300
def __str__(self):
@@ -9450,8 +9456,11 @@ cdef class Camera:
94509456
# \param min[out] : Minimum depth detected (in selected sl.UNIT).
94519457
# \param max[out] : Maximum depth detected (in selected sl.UNIT).
94529458
# \return \ref ERROR_CODE "ERROR_CODE.SUCCESS" if values can be extracted, \ref ERROR_CODE "ERROR_CODE.FAILURE" otherwise.
9453-
def get_current_min_max_depth(self,min: float,max: float) -> ERROR_CODE:
9454-
return ERROR_CODE(<int>self.camera.getCurrentMinMaxDepth(min.float,max.float))
9459+
def get_current_min_max_depth(self) -> (ERROR_CODE, float, float):
9460+
cdef float min
9461+
cdef float max
9462+
error_code = ERROR_CODE(<int>self.camera.getCurrentMinMaxDepth(<float&>min, <float&>max))
9463+
return error_code, min, max
94559464

94569465
##
94579466
# Returns the CameraInformation associated the camera being used.
@@ -11486,7 +11495,7 @@ cdef class GeoPose:
1148611495
self.geopose.latlng_coordinates = value.latLng
1148711496

1148811497
##
11489-
# The heading (orientation) of the pose in degrees (°). It indicates the direction in which the object or observer is facing, with 0 degrees corresponding to North and increasing in a clockwise direction.
11498+
# The heading (orientation) of the pose in radians (rad). It indicates the direction in which the object or observer is facing, with 0 degrees corresponding to North and increasing in a counter-clockwise direction.
1149011499
@property
1149111500
def heading(self):
1149211501
return self.geopose.heading
@@ -11578,6 +11587,8 @@ cdef class GNSSData:
1157811587
def ts(self, value: Timestamp):
1157911588
self.gnss_data.ts = value.timestamp
1158011589

11590+
##
11591+
# Represents the current status of GNSS.
1158111592
@property
1158211593
def gnss_status(self) -> GNSS_STATUS:
1158311594
return GNSS_STATUS(<int>self.gnss_data.gnss_status)
@@ -11586,6 +11597,8 @@ cdef class GNSSData:
1158611597
def gnss_status(self, gnss_status):
1158711598
self.gnss_data.gnss_status = (<c_GNSS_STATUS> (<unsigned int>gnss_status))
1158811599

11600+
##
11601+
# Represents the current mode of GNSS.
1158911602
@property
1159011603
def gnss_mode(self) -> GNSS_MODE:
1159111604
return GNSS_STATUS(<int>self.gnss_data.gnss_mode)

src/pyzed/sl_c.pxd

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -116,6 +116,9 @@ cdef extern from "sl/Camera.hpp" namespace "sl":
116116
ZED2i 'sl::MODEL::ZED2i',
117117
ZED_X 'sl::MODEL::ZED_X',
118118
ZED_XM 'sl::MODEL::ZED_XM',
119+
VIRTUAL_ZED_X 'sl::MODEL::VIRTUAL_ZED_X',
120+
ZED_XONE_GS 'sl::MODEL::ZED_XONE_GS',
121+
ZED_XONE_UHD 'sl::MODEL::ZED_XONE_UHD',
119122
MODEL_LAST 'sl::MODEL::LAST'
120123

121124
String toString(MODEL o)

0 commit comments

Comments
 (0)