Skip to content

Commit 9b50fb8

Browse files
authored
Merge pull request #272 from stereolabs/dev-4.0.7
Update to 4.0.7
2 parents 264d44b + df50ce9 commit 9b50fb8

File tree

11 files changed

+124
-24
lines changed

11 files changed

+124
-24
lines changed

ZEDCamera/Assets/ZED/Editor/Scripts/ZEDCameraEditor.cs

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -166,6 +166,7 @@ public class ZEDCameraEditor : Editor
166166
SerializedProperty openTimeoutSecProperty;
167167
SerializedProperty asyncGrabCameraRecoveryProperty;
168168
SerializedProperty grabComputeCappingFPSProperty;
169+
SerializedProperty enableImageValidityCheckProperty;
169170

170171
// Rendering Prop
171172
private int arlayer;
@@ -364,6 +365,7 @@ private void OnEnable()
364365
openTimeoutSecProperty = serializedObject.FindProperty("openTimeoutSec");
365366
asyncGrabCameraRecoveryProperty = serializedObject.FindProperty("asyncGrabCameraRecovery");
366367
grabComputeCappingFPSProperty = serializedObject.FindProperty("grabComputeCappingFPS");
368+
enableImageValidityCheckProperty = serializedObject.FindProperty("enableImageValidityCheck");
367369

368370
//Video Settings Serialized Properties
369371
videoSettingsInitModeProperty = serializedObject.FindProperty("videoSettingsInitMode");
@@ -1242,10 +1244,18 @@ public override void OnInspectorGUI()
12421244
"Default is 0, which means that the setting is not used.");
12431245
grabComputeCappingFPSProperty.floatValue = EditorGUILayout.FloatField(grabComputeCappingFPSLabel, grabComputeCappingFPSProperty.floatValue);
12441246

1247+
GUIContent enableImageValidityCheckLabel = new GUIContent("Enable Image Validity Check", "Enable or disable the image validity verification." +
1248+
"\nThis will perform additional verification on the image to identify corrupted data. This verification is done in the grab function and requires some computations." +
1249+
"\nIf an issue is found, the grab function will output a warning as sl::ERROR_CODE::CORRUPTED_FRAME." +
1250+
"This version currently doesn't detect frame tearing." +
1251+
"\nDefault: disabled");
1252+
enableImageValidityCheckProperty.boolValue = EditorGUILayout.Toggle(enableImageValidityCheckLabel, enableImageValidityCheckProperty.boolValue);
1253+
12451254
GUILayout.Space(12);
12461255

12471256
EditorGUI.indentLevel--;
12481257

1258+
12491259
EditorGUILayout.LabelField("AR Passthrough Settings", EditorStyles.boldLabel);
12501260
GUILayout.Space(5);
12511261

ZEDCamera/Assets/ZED/SDK/Helpers/Scripts/BodyTracking/HeightOffsetter.cs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@ public class HeightOffsetter : MonoBehaviour
88

99
[Header("Main settings")]
1010

11-
ZEDBodyTrackingManager bodyTrackingManager;
11+
public ZEDBodyTrackingManager bodyTrackingManager;
1212

1313
[SerializeField]
1414
private float currentAutoHeightOffset = 0f;

ZEDCamera/Assets/ZED/SDK/Helpers/Scripts/BodyTracking/SkeletonHandler.cs

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -436,6 +436,7 @@ public const int
436436

437437
private GameObject humanoid;
438438
public ZEDSkeletonAnimator zedSkeletonAnimator = null;
439+
public ZEDBodyTrackingManager zedBodyTrackingManager = null;
439440
private Animator animator;
440441
private Dictionary<HumanBodyBones, RigBone> rigBone = null;
441442
private Dictionary<HumanBodyBones, Quaternion> rigBoneTarget = null;
@@ -529,7 +530,7 @@ public Animator GetAnimator()
529530
/// </summary>
530531
/// <param name="h">The humanoid GameObject prefab.</param>
531532
/// <param name="body_format">The Body model to apply (34 or 38 bones).</param>
532-
public void Create(GameObject h, sl.BODY_FORMAT body_format)
533+
public void Create(GameObject h, sl.BODY_FORMAT body_format, ZEDBodyTrackingManager btmanager)
533534
{
534535
humanoid = (GameObject)Instantiate(h, Vector3.zero, Quaternion.identity);
535536
animator = humanoid.GetComponent<Animator>();
@@ -538,6 +539,7 @@ public void Create(GameObject h, sl.BODY_FORMAT body_format)
538539

539540
zedSkeletonAnimator = humanoid.GetComponent<ZEDSkeletonAnimator>();
540541
zedSkeletonAnimator.Skhandler = this;
542+
zedSkeletonAnimator.BodyTrackingManager = btmanager;
541543

542544
// Init list of bones that will be updated by the data retrieved from the ZED SDK
543545
rigBone = new Dictionary<HumanBodyBones, RigBone>();

ZEDCamera/Assets/ZED/SDK/Helpers/Scripts/BodyTracking/ZEDBodyTrackingManager.cs

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -208,7 +208,7 @@ void OnDestroy()
208208
IEnumerator InstanciateAvatarWithDelay(float delay, DetectedBody dbody)
209209
{
210210
SkeletonHandler handler = ScriptableObject.CreateInstance<SkeletonHandler>();
211-
handler.Create(avatar, bodyFormat);
211+
handler.Create(avatar, bodyFormat, this);
212212
handler.InitSkeleton(dbody.rawBodyData.id, new Material(skeletonBaseMaterial));
213213

214214
avatarControlList.Add(dbody.rawBodyData.id, handler);

ZEDCamera/Assets/ZED/SDK/Helpers/Scripts/BodyTracking/ZEDSkeletonAnimator.cs

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -280,17 +280,13 @@ public void TryShowAvatar(bool newVisibility)
280280

281281
private void Awake()
282282
{
283-
bodyTrackingManager = FindObjectOfType<ZEDBodyTrackingManager>();
284-
if (bodyTrackingManager == null)
285-
{
286-
Debug.LogError("ZEDManagerIK: No body tracking manager loaded!");
287-
}
288283
heightOffsetter = GetComponent<HeightOffsetter>();
289284
}
290285

291286
void Start()
292287
{
293288
animator = GetComponent<Animator>();
289+
heightOffsetter.bodyTrackingManager = bodyTrackingManager;
294290
}
295291

296292
private void Update()

ZEDCamera/Assets/ZED/SDK/Helpers/Scripts/Display/ZEDRenderingPlane.cs

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -115,6 +115,8 @@ public Camera renderingCam
115115
/// </summary>
116116
Texture2D depth;
117117

118+
public Texture2D Depth { get { return depth; } }
119+
118120
/// <summary>
119121
/// Normals generated by the ZEDCamera.
120122
/// Once created, the ZED SDK automatically updates it whenever the ZED captures new frames/images.

ZEDCamera/Assets/ZED/SDK/Helpers/Scripts/ZEDManager.cs

Lines changed: 24 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -142,6 +142,17 @@ public static List<ZEDManager> GetInstances()
142142
[HideInInspector]
143143
public float grabComputeCappingFPS = 0f;
144144

145+
/// <summary>
146+
/// Define a computation upper limit to the grab frequency. 0 means setting is ignored.
147+
/// This can be useful to get a known constant fixed rate or limit the computation load while keeping a short exposure time by setting a high camera capture framerate.
148+
/// The value should be inferior to the InitParameters::camera_fps and strictly positive.It has no effect when reading an SVO file.
149+
/// This is an upper limit and won't make a difference if the computation is slower than the desired compute capping fps.
150+
/// Internally the grab function always tries to get the latest available image while respecting the desired fps as much as possible.
151+
/// default is 0.
152+
/// </summary>
153+
[HideInInspector]
154+
public bool enableImageValidityCheck = false;
155+
145156
/// <summary>
146157
/// SVO loop back option
147158
/// </summary>
@@ -2068,6 +2079,7 @@ void Awake()
20682079
initParameters.openTimeoutSec = openTimeoutSec;
20692080
initParameters.asyncGrabCameraRecovery = asyncGrabCameraRecovery;
20702081
initParameters.grabComputeCappingFPS = grabComputeCappingFPS;
2082+
initParameters.enableImageValidityCheck = enableImageValidityCheck;
20712083

20722084
//Check if this rig is a stereo rig. Will set isStereoRig accordingly.
20732085
CheckStereoMode();
@@ -2186,7 +2198,6 @@ private void OpenZEDInBackground()
21862198
{
21872199
initQuittingHandle.WaitOne(0); //Makes sure we haven't been turned off early, which only happens in Destroy() from OnApplicationQuit().
21882200
if (forceCloseInit) break;
2189-
21902201
lastInitStatus = zedCamera.Open(ref initParameters);
21912202
timeout++;
21922203
numberTriesOpening++;
@@ -3562,17 +3573,12 @@ void CreateMirror()
35623573
}
35633574
#endregion
35643575

3565-
/// <summary>
3566-
/// Closes out the current stream, then starts it up again while maintaining tracking data.
3567-
/// Used when the zed becomes unplugged, or you want to change a setting at runtime that
3568-
/// requires re-initializing the camera.
3569-
/// </summary>
3570-
public void Reset()
3576+
public void Close()
35713577
{
35723578
//Save tracking
35733579
if (enableTracking && isTrackingEnable)
35743580
{
3575-
zedCamera.GetPosition(ref zedOrientation, ref zedPosition);
3581+
if (zedCamera != null) zedCamera.GetPosition(ref zedOrientation, ref zedPosition);
35763582
}
35773583

35783584
CloseManager();
@@ -3581,6 +3587,16 @@ public void Reset()
35813587
running = false;
35823588
numberTriesOpening = 0;
35833589
forceCloseInit = false;
3590+
}
3591+
3592+
/// <summary>
3593+
/// Closes out the current stream, then starts it up again while maintaining tracking data.
3594+
/// Used when the zed becomes unplugged, or you want to change a setting at runtime that
3595+
/// requires re-initializing the camera.
3596+
/// </summary>
3597+
public void Reset()
3598+
{
3599+
Close();
35843600

35853601
Awake();
35863602
}

ZEDCamera/Assets/ZED/SDK/NativeInterface/ZEDCamera.cs

Lines changed: 45 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -285,7 +285,7 @@ public int TagInvisibleToZED
285285
/// <summary>
286286
/// Current Plugin Version.
287287
/// </summary>
288-
public static readonly System.Version PluginVersion = new System.Version(4, 0, 6);
288+
public static readonly System.Version PluginVersion = new System.Version(4, 0, 7);
289289

290290
/******** DLL members ***********/
291291
[DllImport(nameDll, EntryPoint = "GetRenderEventFunc")]
@@ -413,6 +413,9 @@ public int TagInvisibleToZED
413413
* Camera control functions.
414414
*/
415415

416+
[DllImport(nameDll, EntryPoint = "sl_is_camera_setting_supported")]
417+
private static extern bool dllz_is_video_setting_supported(int id, int setting);
418+
416419
[DllImport(nameDll, EntryPoint = "sl_set_video_settings")]
417420
private static extern void dllz_set_video_settings(int id, int mode, int value);
418421

@@ -499,16 +502,18 @@ public int TagInvisibleToZED
499502
[DllImport(nameDll, EntryPoint = "sl_get_svo_position")]
500503
private static extern int dllz_get_svo_position(int cameraID);
501504

505+
[DllImport(nameDll, EntryPoint = "sl_get_svo_position_at_timestamp")]
506+
private static extern int dllz_get_svo_position_at_timestamp(int cameraID, ulong timestamp);
502507

503508
/*
504509
* Depth Sensing utils functions.
505510
*/
506-
/* Removed as of ZED SDK v3.0.
507-
[DllImport(nameDll, EntryPoint = "set_confidence_threshold")]
508-
private static extern void dllz_set_confidence_threshold(int cameraID, int threshold);
509-
[DllImport(nameDll, EntryPoint = "set_depth_max_range_value")]
510-
private static extern void dllz_set_depth_max_range_value(int cameraID, float distanceMax);
511-
*/
511+
/* Removed as of ZED SDK v3.0.
512+
[DllImport(nameDll, EntryPoint = "set_confidence_threshold")]
513+
private static extern void dllz_set_confidence_threshold(int cameraID, int threshold);
514+
[DllImport(nameDll, EntryPoint = "set_depth_max_range_value")]
515+
private static extern void dllz_set_depth_max_range_value(int cameraID, float distanceMax);
516+
*/
512517

513518
[DllImport(nameDll, EntryPoint = "sl_get_confidence_threshold")]
514519
private static extern int dllz_get_confidence_threshold(int cameraID);
@@ -1083,6 +1088,16 @@ public struct dll_initParameters
10831088
/// </summary>
10841089
public float grabComputeCappingFPS;
10851090

1091+
/// <summary>
1092+
/// Enable or disable the image validity verification.
1093+
/// This will perform additional verification on the image to identify corrupted data. This verification is done in the grab function and requires some computations.
1094+
/// If an issue is found, the grab function will output a warning as sl::ERROR_CODE::CORRUPTED_FRAME.
1095+
/// This version doesn't detect frame tearing currently.
1096+
/// \n default: disabled
1097+
/// </summary>
1098+
[MarshalAs(UnmanagedType.U1)]
1099+
public bool enableImageValidityCheck;
1100+
10861101
/// <summary>
10871102
/// Copy constructor. Takes values from Unity-suited InitParameters class.
10881103
/// </summary>
@@ -1110,6 +1125,7 @@ public dll_initParameters(InitParameters init)
11101125
openTimeoutSec = init.openTimeoutSec;
11111126
asyncGrabRecovery = init.asyncGrabCameraRecovery;
11121127
grabComputeCappingFPS = init.grabComputeCappingFPS;
1128+
enableImageValidityCheck = init.enableImageValidityCheck;
11131129
}
11141130
}
11151131

@@ -1130,7 +1146,8 @@ public ERROR_CODE Open(ref InitParameters initParameters)
11301146
initParameters.cameraFPS = (int)fpsMax;
11311147
}
11321148
dll_initParameters initP = new dll_initParameters(initParameters); //DLL-friendly version of InitParameters.
1133-
initP.coordinateSystem = COORDINATE_SYSTEM.LEFT_HANDED_Y_UP; //Left-hand, Y-up is Unity's coordinate system, so we match that.
1149+
initP.coordinateSystem = COORDINATE_SYSTEM.LEFT_HANDED_Y_UP; //Left-hand, Y-up is Unity's coordinate system, so we match that
1150+
11341151
int v = dllz_open(CameraID, ref initP, initParameters.serialNumber,
11351152
new System.Text.StringBuilder(initParameters.pathSVO, initParameters.pathSVO.Length),
11361153
new System.Text.StringBuilder(initParameters.ipStream, initParameters.ipStream.Length),
@@ -1322,6 +1339,16 @@ public int GetSVOPosition()
13221339
return dllz_get_svo_position(CameraID);
13231340
}
13241341

1342+
/// <summary>
1343+
/// Retrieves the frame index within the SVO file corresponding to the provided timestamp.
1344+
/// </summary>
1345+
/// <param name="timestamp">The target timestamp for which the frame index is to be determined.</param>
1346+
/// <returns>The frame index within the SVO file that aligns with the given timestamp. Returns -1 if the timestamp falls outside the bounds of the SVO file.</returns>
1347+
public int GetSVOPositionAtTimestamp(ulong timestamp)
1348+
{
1349+
return dllz_get_svo_position_at_timestamp(CameraID, timestamp);
1350+
}
1351+
13251352
/// <summary>
13261353
/// Gets the total number of frames in the loaded SVO file.
13271354
/// </summary>
@@ -1981,6 +2008,16 @@ static public void Float2Matrix(ref Matrix4x4 m, float[] f)
19812008
}
19822009
}
19832010

2011+
/// <summary>
2012+
/// Test if the video setting is supported by the camera
2013+
/// setting : The video setting to test
2014+
/// true if the \ref SL_VIDEO_SETTINGS is supported by the camera, false otherwise
2015+
/// </summary>
2016+
public bool IsCameraSettingSupported(CAMERA_SETTINGS setting)
2017+
{
2018+
return dllz_is_video_setting_supported(CameraID, (int)setting);
2019+
}
2020+
19842021
/// <summary>
19852022
/// Sets a value in the ZED's camera settings.
19862023
/// </summary>

ZEDCamera/Assets/ZED/SDK/NativeInterface/ZEDCommon.cs

Lines changed: 37 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -816,6 +816,13 @@ public enum VIEW_MODE
816816
/// </remarks>
817817
public enum ERROR_CODE
818818
{
819+
/// <summary>
820+
/// The image could be corrupted, Enabled with the parameter InitParameters::enableImageValidityCheck.
821+
/// </summary>
822+
CORRUPTED_FRAME = -2,
823+
/// <summary>
824+
/// The camera is currently rebooting.
825+
/// </summary>
819826
CAMERA_REBOOTING = -1,
820827
/// <summary>
821828
/// Operation was successful.
@@ -1131,6 +1138,7 @@ public enum VIEW
11311138

11321139
/// <summary>
11331140
/// Lists available camera settings for the ZED camera (contrast, hue, saturation, gain, etc.)
1141+
/// The settings specific for GMSL cameras are currently not supported.
11341142
/// </summary>
11351143
public enum CAMERA_SETTINGS
11361144
{
@@ -1364,6 +1372,25 @@ public enum POSTIONAL_TRACKING_MODE
13641372
QUALITY
13651373
}
13661374

1375+
/// <summary>
1376+
/// Lists the mode of positional tracking that can be used.
1377+
/// </summary>
1378+
public enum REGION_OF_INTEREST_AUTO_DETECTION_STATE
1379+
{
1380+
/// <summary>
1381+
/// The region of interest auto detection is initializing.
1382+
/// </summary>
1383+
RUNNING,
1384+
/// <summary>
1385+
/// The region of interest mask is ready, if auto_apply was enabled, the region of interest mask is being used.
1386+
/// </summary>
1387+
READY,
1388+
/// <summary>
1389+
/// The region of interest auto detection is not enabled.
1390+
/// </summary>
1391+
ENABLED,
1392+
}
1393+
13671394
/// <summary>
13681395
/// SVO compression modes.
13691396
/// </summary>
@@ -1660,6 +1687,15 @@ public class InitParameters
16601687
/// </summary>
16611688
public float grabComputeCappingFPS = 0f;
16621689

1690+
/// <summary>
1691+
/// Enable or disable the image validity verification.
1692+
/// This will perform additional verification on the image to identify corrupted data. This verification is done in the grab function and requires some computations.
1693+
/// If an issue is found, the grab function will output a warning as sl::ERROR_CODE::CORRUPTED_FRAME.
1694+
/// This version doesn't detect frame tearing currently.
1695+
/// \n default: disabled
1696+
/// </summary>
1697+
public bool enableImageValidityCheck = false;
1698+
16631699
/// <summary>
16641700
/// Constructor. Sets default initialization parameters recommended for Unity.
16651701
/// </summary>
@@ -1693,6 +1729,7 @@ public InitParameters()
16931729
this.openTimeoutSec = 5.0f;
16941730
this.asyncGrabCameraRecovery = false;
16951731
this.grabComputeCappingFPS = 0f;
1732+
this.enableImageValidityCheck = false;
16961733
}
16971734
}
16981735

158 KB
Binary file not shown.

0 commit comments

Comments
 (0)