Skip to content

Commit 2cc7868

Browse files
JujuDelJulien Delclos
andauthored
r5.1.1 (#260)
Co-authored-by: Julien Delclos <[email protected]>
1 parent 78e0075 commit 2cc7868

File tree

2 files changed

+23
-9
lines changed

2 files changed

+23
-9
lines changed

src/pyzed/sl.pyx

Lines changed: 22 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -8906,15 +8906,13 @@ cdef class InitParameters:
89068906
# Minimum depth distance to be returned, measured in the sl.UNIT defined in \ref coordinate_units.
89078907
#
89088908
# This parameter allows you to specify the minimum depth value (from the camera) that will be computed.
8909+
# \n Setting this value to any negative or null value will select the default minimum depth distance available for the used ZED Camera (depending on the camera focal length and baseline).
8910+
# \n Default: -1
89098911
#
8910-
# \n In stereovision (the depth technology used by the camera), looking for closer depth values can have a slight impact on performance and memory consumption.
8911-
# \n On most of modern GPUs, performance impact will be low. However, the impact of memory footprint will be visible.
8912-
# \n In cases of limited computation power, increasing this value can provide better performance.
8913-
# \n Default: -1 (corresponding values are available <a href="https://www.stereolabs.com/docs/depth-sensing/depth-settings#depth-range">here</a>)
8912+
# \n When using deprecated depth modes ( \ref sl.DEPTH_MODE.PERFORMANCE, \ref sl.DEPTH_MODE.QUALITY or \ref sl.DEPTH_MODE.ULTRA),
8913+
# the default minimum depth distances are given by <a href="https://www.stereolabs.com/docs/depth-sensing/depth-settings#depth-range">this table</a>.
89148914
#
8915-
# \note \ref depth_minimum_distance value cannot be greater than 3 meters.
8916-
# \note 0 will imply that \ref depth_minimum_distance is set to the minimum depth possible for each camera
8917-
# (those values are available <a href="https://www.stereolabs.com/docs/depth-sensing/depth-settings#depth-range">here</a>).
8915+
# \note This value cannot be greater than 3 meters.
89188916
@property
89198917
def depth_minimum_distance(self) -> float:
89208918
return self.init.depth_minimum_distance
@@ -8927,8 +8925,11 @@ cdef class InitParameters:
89278925
# Maximum depth distance to be returned, measured in the sl.UNIT defined in \ref coordinate_units.
89288926
#
89298927
# When estimating the depth, the ZED SDK uses this upper limit to turn higher values into <b>inf</b> ones.
8930-
# \note Changing this value has no impact on performance and doesn't affect the positional tracking nor the spatial mapping.
8931-
# \note It only change values the depth, point cloud and normals.
8928+
# \n Changing this value has no impact on performance and doesn't affect the positional tracking nor the spatial mapping.
8929+
# \n It only change values the depth, point cloud and normals.
8930+
# \n Setting this value to any negative or null value will select the default maximum depth distance available.
8931+
#
8932+
# \n Default: -1
89328933
@property
89338934
def depth_maximum_distance(self) -> float:
89348935
return self.init.depth_maximum_distance
@@ -13292,6 +13293,18 @@ cdef class FusionConfiguration:
1329213293
# Reset the reference `_input_type_ref` so it gets recreated next time
1329313294
self._input_type_initialized = False
1329413295

13296+
##
13297+
# Indicates the behavior of the fusion with respect to given calibration pose.
13298+
# - If true : The calibration pose directly specifies the camera's absolute pose relative to a global reference frame.
13299+
# - If false : The calibration pose (Pose_rel) is defined relative to the camera's IMU rotational pose. To determine the true absolute position, the Fusion process will compute Pose_abs = Pose_rel * Rot_IMU_camera.
13300+
@property
13301+
def override_gravity(self) -> bool:
13302+
return self.fusionConfiguration.override_gravity
13303+
13304+
@override_gravity.setter
13305+
def override_gravity(self, bool value):
13306+
self.fusionConfiguration.override_gravity = value
13307+
1329513308
##
1329613309
# Read a configuration JSON file to configure a fusion process.
1329713310
# \ingroup Fusion_group

src/pyzed/sl_c.pxd

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1992,6 +1992,7 @@ cdef extern from "sl/Fusion.hpp" namespace "sl":
19921992
CommunicationParameters communication_parameters
19931993
Transform pose
19941994
InputType input_type
1995+
bool override_gravity
19951996

19961997
cdef cppclass CommunicationParameters 'sl::CommunicationParameters':
19971998
CommunicationParameters()

0 commit comments

Comments
 (0)