123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569157015711572157315741575157615771578157915801581158215831584158515861587158815891590159115921593159415951596159715981599160016011602160316041605160616071608160916101611161216131614161516161617161816191620162116221623162416251626162716281629163016311632163316341635163616371638163916401641164216431644164516461647164816491650165116521653165416551656165716581659166016611662166316641665166616671668166916701671167216731674167516761677167816791680168116821683168416851686168716881689169016911692169316941695169616971698169917001701170217031704170517061707170817091710171117121713171417151716171717181719172017211722172317241725172617271728172917301731173217331734173517361737173817391740174117421743174417451746174717481749175017511752175317541755175617571758175917601761176217631764176517661767176817691770177117721773177417751776177717781779178017811782178317841785178617871788178917901791179217931794179517961797179817991800180118021803180418051806180718081809181018111812181318141815181618171818181918201821182218231824182518261827182818291830183118321833183418351836183718381839184018411842184318441845184618471848184918501851185218531854185518561857185818591860186118621863186418651866186718681869187018711872187318741875187618771878187918801881188218831884188518861887188818891890189118921893189418951896189718981899190019011902190319041905190619071908190919101911191219131914191519161917191819191920192119221923192419251926192719281929193019311932193319341935193619371938193919401941194219431944194519461947194819491950195119521953195419551956195719581959196019611962196319641965196619671968196919701971197219731974197519761977197819791980198119821983198419851986198719881989199019911992199319941995199619971998199920002001200220032004200520062007200820092010201120122013201420152016201720182019202020212022202320242025202620272028202920302031203220332034203520362037203820392040204120422043204420452046204720482049205020512052205320542055205620572058205920602061206220632064206520662067206820692070207120722073207420752076207720782079208020812082208320842085208620872088208920902091209220932094209520962097209820992100210121022103210421052106210721082109211021112112211321142115211621172118211921202121212221232124212521262127212821292130213121322133213421352136213721382139214021412142214321442145214621472148214921502151215221532154215521562157215821592160216121622163216421652166216721682169217021712172217321742175217621772178217921802181218221832184218521862187218821892190219121922193219421952196219721982199220022012202220322042205220622072208220922102211221222132214221522162217221822192220222122222223222422252226222722282229223022312232223322342235223622372238223922402241224222432244224522462247224822492250225122522253225422552256225722582259226022612262 |
- //======= Copyright (c) Stereolabs Corporation, All rights reserved. ===============
- using System.Runtime.InteropServices;
- using System;
- using System.Collections.Generic;
- using UnityEngine;
- /// <summary>
- /// This file holds classes built to be exchanged between the ZED wrapper DLL (sl_unitywrapper.dll)
- /// and C# scripts within Unity. Most have parity with a structure within the ZED C++ SDK.
- /// Find more info at https://www.stereolabs.com/developers/documentation/API/latest/.
- /// </summary>
- namespace sl
- {
- public class ZEDCommon
- {
- public const string NameDLL = "sl_unitywrapper";
- }
- public enum ZED_CAMERA_ID
- {
- CAMERA_ID_01,
- CAMERA_ID_02,
- CAMERA_ID_03,
- CAMERA_ID_04
- };
- public enum INPUT_TYPE
- {
- INPUT_TYPE_USB,
- INPUT_TYPE_SVO,
- INPUT_TYPE_STREAM
- };
- /// <summary>
- /// Constant for plugin. Should not be changed
- /// </summary>
- public enum Constant
- {
- MAX_CAMERA_PLUGIN = 4,
- PLANE_DISTANCE = 10,
- MAX_OBJECTS = 75,
- MAX_BATCH_SIZE = 200
- };
- /// <summary>
- /// Holds a 3x3 matrix that can be marshaled between the ZED
- /// Unity wrapper and C# scripts.
- /// </summary>
- public struct Matrix3x3
- {
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = 9)]
- public float[] m; //3x3 matrix.
- };
- /// <summary>
- /// Holds a camera resolution as two pointers (for height and width) for easy
- /// passing back and forth to the ZED Unity wrapper.
- /// </summary>
- public struct Resolution
- {
- /// <summary>
- ///
- /// </summary>
- /// <param name="width"></param>
- /// <param name="height"></param>
- public Resolution(uint width, uint height)
- {
- this.width = (System.UIntPtr)width;
- this.height = (System.UIntPtr)height;
- }
- public System.UIntPtr width;
- public System.UIntPtr height;
- };
- /// <summary>
- /// Pose structure with data on timing and validity in addition to
- /// position and rotation.
- /// </summary>
- [StructLayout(LayoutKind.Sequential)]
- public struct Pose
- {
- public bool valid;
- public ulong timestap;
- public Quaternion rotation;
- public Vector3 translation;
- public int pose_confidence;
- };
- /// <summary>
- /// Rect structure to define a rectangle or a ROI in pixels
- /// Use to set ROI target for AEC/AGC
- /// </summary>
- [StructLayout(LayoutKind.Sequential)]
- public struct iRect
- {
- public int x;
- public int y;
- public int width;
- public int height;
- };
- public enum CAMERA_STATE
- {
- /// <summary>
- /// Defines if the camera can be openned by the sdk
- /// </summary>
- AVAILABLE,
- /// <summary>
- /// Defines if the camera is already opened and unavailable
- /// </summary>
- NOT_AVAILABLE
- }
- [StructLayout(LayoutKind.Sequential)]
- public struct DeviceProperties
- {
- /// <summary>
- /// The camera state
- /// </summary>
- public sl.CAMERA_STATE cameraState;
- /// <summary>
- /// The camera id (Notice that only the camera with id '0' can be used on Windows)
- /// </summary>
- public int id;
- /// <summary>
- /// The camera model
- /// </summary>
- public sl.MODEL cameraModel;
- /// <summary>
- /// The camera serial number
- /// </summary>
- public int sn;
- };
- /// <summary>
- /// Full IMU data structure.
- /// </summary>
- [StructLayout(LayoutKind.Sequential)]
- public struct ImuData
- {
- /// <summary>
- /// Indicates if imu data is available
- /// </summary>
- public bool available;
- /// <summary>
- /// IMU Data timestamp in ns
- /// </summary>
- public ulong timestamp;
- /// <summary>
- /// Gyroscope calibrated data in degrees/second.
- /// </summary>
- public Vector3 angularVelocity;
- /// <summary>
- /// Accelerometer calibrated data in m/s².
- /// </summary>
- public Vector3 linearAcceleration;
- /// <summary>
- /// Gyroscope raw/uncalibrated data in degrees/second.
- /// </summary>
- public Vector3 angularVelocityUncalibrated;
- /// <summary>
- /// Accelerometer raw/uncalibrated data in m/s².
- /// </summary>
- public Vector3 linearAccelerationUncalibrated;
- /// <summary>
- /// Orientation from gyro/accelerator fusion.
- /// </summary>
- public Quaternion fusedOrientation;
- /// <summary>
- /// Covariance matrix of the quaternion.
- /// </summary>
- public Matrix3x3 orientationCovariance;
- /// <summary>
- /// Gyroscope raw data covariance matrix.
- /// </summary>
- public Matrix3x3 angularVelocityCovariance;
- /// <summary>
- /// Accelerometer raw data covariance matrix.
- /// </summary>
- public Matrix3x3 linearAccelerationCovariance;
- };
- [StructLayout(LayoutKind.Sequential)]
- public struct BarometerData
- {
- /// <summary>
- /// Indicates if mag data is available
- /// </summary>
- public bool available;
- /// <summary>
- /// mag Data timestamp in ns
- /// </summary>
- public ulong timestamp;
- /// <summary>
- /// Barometer ambient air pressure in hPa
- /// </summary>
- public float pressure;
- /// <summary>
- /// Relative altitude from first camera position
- /// </summary>
- public float relativeAltitude;
- };
- public enum HEADING_STATE
- {
- /// <summary>
- /// The heading is reliable and not affected by iron interferences.
- /// </summary>
- GOOD,
- /// <summary>
- /// The heading is reliable, but affected by slight iron interferences.
- /// </summary>
- OK,
- /// <summary>
- /// The heading is not reliable because affected by strong iron interferences.
- /// </summary>
- NOT_GOOD,
- /// <summary>
- /// The magnetometer has not been calibrated.
- /// </summary>
- NOT_CALIBRATED,
- /// <summary>
- /// The magnetomer sensor is not available.
- /// </summary>
- MAG_NOT_AVAILABLE
- };
- [StructLayout(LayoutKind.Sequential)]
- public struct MagnetometerData
- {
- /// <summary>
- /// Indicates if mag data is available
- /// </summary>
- public bool available;
- /// <summary>
- /// mag Data timestamp in ns
- /// </summary>
- public ulong timestamp;
- /// <summary>
- /// Magnetic field calibrated values in uT
- /// </summary>
- /// </summary>
- public Vector3 magneticField;
- /// <summary>
- /// Magnetic field raw values in uT
- /// </summary>
- public Vector3 magneticFieldUncalibrated;
- /// <summary>
- /// The camera heading in degrees relative to the magnetic North Pole.
- /// note: The magnetic North Pole has an offset with respect to the geographic North Pole, depending on the
- /// geographic position of the camera.
- /// To get a correct magnetic heading the magnetometer sensor must be calibrated using the ZED Sensor Viewer tool
- /// </summary>
- public float magneticHeading;
- /// <summary>
- /// The state of the /ref magnetic_heading value
- /// </summary>
- public HEADING_STATE magnetic_heading_state;
- /// <summary>
- /// The accuracy of the magnetic heading measure in the range [0.0,1.0].
- /// A negative value means that the magnetometer must be calibrated using the ZED Sensor Viewer tool
- /// </summary>
- public float magnetic_heading_accuracy;
- };
- [StructLayout(LayoutKind.Sequential)]
- public struct TemperatureSensorData
- {
- /// <summary>
- /// Temperature from IMU device ( -100 if not available)
- /// </summary>
- public float imu_temp;
- /// <summary>
- /// Temperature from Barometer device ( -100 if not available)
- /// </summary>
- public float barometer_temp;
- /// <summary>
- /// Temperature from Onboard left analog temperature sensor ( -100 if not available)
- /// </summary>
- public float onboard_left_temp;
- /// <summary>
- /// Temperature from Onboard right analog temperature sensor ( -100 if not available)
- /// </summary>
- public float onboard_right_temp;
- };
- [StructLayout(LayoutKind.Sequential)]
- public struct SensorsData
- {
- /// <summary>
- /// Contains Imu Data
- /// </summary>
- public ImuData imu;
- /// <summary>
- /// Contains Barometer Data
- /// </summary>
- public BarometerData barometer;
- /// <summary>
- /// Contains Mag Data
- /// </summary>
- public MagnetometerData magnetometer;
- /// <summary>
- /// Contains Temperature Data
- /// </summary>
- public TemperatureSensorData temperatureSensor;
- /// <summary>
- /// Indicated if camera is :
- /// -> Static : 0
- /// -> Moving : 1
- /// -> Falling : 2
- /// </summary>
- public int camera_moving_state;
- /// <summary>
- /// Indicates if the current sensors data is sync to the current image (>=1). Otherwise, value will be 0.
- /// </summary>
- public int image_sync_val;
- };
- /*******************************************************************************************************************************
- *******************************************************************************************************************************/
- /// <summary>
- /// Calibration information for an individual sensor on the ZED (left or right). </summary>
- /// <remarks>For more information, see:
- /// https://www.stereolabs.com/developers/documentation/API/v2.5.1/structsl_1_1CameraParameters.html </remarks>
- [StructLayout(LayoutKind.Sequential)]
- public struct CameraParameters
- {
- /// <summary>
- /// Focal X.
- /// </summary>
- public float fx;
- /// <summary>
- /// Focal Y.
- /// </summary>
- public float fy;
- /// <summary>
- /// Optical center X.
- /// </summary>
- public float cx;
- /// <summary>
- /// Optical center Y.
- /// </summary>
- public float cy;
- /// <summary>
- /// Distortion coefficients.
- /// </summary>
- [MarshalAs(UnmanagedType.ByValArray, ArraySubType = UnmanagedType.U8, SizeConst = 5)]
- public double[] disto;
- /// <summary>
- /// Vertical field of view after stereo rectification.
- /// </summary>
- public float vFOV;
- /// <summary>
- /// Horizontal field of view after stereo rectification.
- /// </summary>
- public float hFOV;
- /// <summary>
- /// Diagonal field of view after stereo rectification.
- /// </summary>
- public float dFOV;
- /// <summary>
- /// Camera's current resolution.
- /// </summary>
- public Resolution resolution;
- };
- /// <summary>
- /// List of the available onboard sensors
- /// </summary>
- public enum SENSOR_TYPE
- {
- /// <summary>
- /// Three axis Accelerometer sensor to measure the inertial accelerations.
- /// </summary>
- ACCELEROMETER,
- /// <summary>
- /// Three axis Gyroscope sensor to measure the angular velocitiers.
- /// </summary>
- GYROSCOPE,
- /// <summary>
- /// Three axis Magnetometer sensor to measure the orientation of the device respect to the earth magnetic field.
- /// </summary>
- MAGNETOMETER,
- /// <summary>
- /// Barometer sensor to measure the atmospheric pressure.
- /// </summary>
- BAROMETER,
- LAST
- };
- /// <summary>
- /// List of the available onboard sensors measurement units
- /// </summary>
- public enum SENSORS_UNIT
- {
- /// <summary>
- /// Acceleration [m/s²].
- /// </summary>
- M_SEC_2,
- /// <summary>
- /// Angular velocity [deg/s].
- /// </summary>
- DEG_SEC,
- /// <summary>
- /// Magnetic Fiels [uT].
- /// </summary>
- U_T,
- /// <summary>
- /// Atmospheric pressure [hPa].
- /// </summary>
- HPA,
- /// <summary>
- /// Temperature [°C].
- /// </summary>
- CELSIUS,
- /// <summary>
- /// Frequency [Hz].
- /// </summary>
- HERTZ,
- /// <summary>
- ///
- /// </summary>
- LAST
- };
- /// <summary>
- /// Structure containing information about a single sensor available in the current device
- /// </summary>
- [StructLayout(LayoutKind.Sequential)]
- public struct SensorParameters
- {
- /// <summary>
- /// The type of the sensor as \ref DEVICE_SENSORS.
- /// </summary>
- public SENSOR_TYPE type;
- /// <summary>
- /// The resolution of the sensor.
- /// </summary>
- public float resolution;
- /// <summary>
- /// The sampling rate (or ODR) of the sensor.
- /// </summary>
- public float sampling_rate;
- /// <summary>
- /// The range values of the sensor. MIN: `range.x`, MAX: `range.y`
- /// </summary>
- public float2 range;
- /// <summary>
- /// also known as white noise, given as continous (frequency independant). Units will be expressed in sensor_unit/√(Hz). `NAN` if the information is not available.
- /// </summary>
- public float noise_density;
- /// <summary>
- /// derived from the Allan Variance, given as continous (frequency independant). Units will be expressed in sensor_unit/s/√(Hz).`NAN` if the information is not available.
- /// </summary>
- public float random_walk;
- /// <summary>
- /// The string relative to the measurement unit of the sensor.
- /// </summary>
- public SENSORS_UNIT sensor_unit;
- /// <summary>
- ///
- /// </summary>
- public bool isAvailable;
- };
- /// <summary>
- /// Structure containing information about all the sensors available in the current device
- /// </summary>
- [StructLayout(LayoutKind.Sequential)]
- public struct SensorsConfiguration
- {
- /// <summary>
- /// The firmware version of the sensor module, 0 if no sensors are available (ZED camera model).
- /// </summary>
- public uint firmware_version;
- /// <summary>
- /// contains rotation between IMU frame and camera frame.
- /// </summary>
- public float4 camera_imu_rotation;
- /// <summary>
- /// contains translation between IMU frame and camera frame.
- /// </summary>
- public float3 camera_imu_translation;
- /// <summary>
- /// Magnetometer to IMU rotation. contains rotation between IMU frame and magnetometer frame.
- /// </summary>
- public float4 imu_magnometer_rotation;
- /// <summary>
- /// Magnetometer to IMU translation. contains translation between IMU frame and magnetometer frame.
- /// </summary>
- public float3 imu_magnometer_translation;
- /// <summary>
- /// Configuration of the accelerometer device.
- /// </summary>
- public SensorParameters accelerometer_parameters;
- /// <summary>
- /// Configuration of the gyroscope device.
- /// </summary>
- public SensorParameters gyroscope_parameters;
- /// <summary>
- /// Configuration of the magnetometer device.
- /// </summary>
- public SensorParameters magnetometer_parameters;
- /// <summary>
- /// Configuration of the barometer device
- /// </summary>
- public SensorParameters barometer_parameters;
- /// <summary>
- /// if a sensor type is available on the device
- /// </summary>
- /// <param name="sensor_type"></param>
- /// <returns></returns>
- public bool isSensorAvailable(SENSOR_TYPE sensor_type)
- {
- switch (sensor_type)
- {
- case SENSOR_TYPE.ACCELEROMETER:
- return accelerometer_parameters.isAvailable;
- case SENSOR_TYPE.GYROSCOPE:
- return gyroscope_parameters.isAvailable;
- case SENSOR_TYPE.MAGNETOMETER:
- return magnetometer_parameters.isAvailable;
- case SENSOR_TYPE.BAROMETER:
- return barometer_parameters.isAvailable;
- default:
- break;
- }
- return false;
- }
- };
- /// <summary>
- /// Holds calibration information about the current ZED's hardware, including per-sensor
- /// calibration and offsets between the two sensors.
- /// </summary> <remarks>For more info, see:
- /// https://www.stereolabs.com/developers/documentation/API/v2.5.1/structsl_1_1CalibrationParameters.html </remarks>
- [StructLayout(LayoutKind.Sequential)]
- public struct CalibrationParameters
- {
- /// <summary>
- /// Parameters of the left sensor.
- /// </summary>
- public CameraParameters leftCam;
- /// <summary>
- /// Parameters of the right sensor.
- /// </summary>
- public CameraParameters rightCam;
- /// <summary>
- /// Rotation (using Rodrigues' transformation) between the two sensors. Defined as 'tilt', 'convergence' and 'roll'.
- /// </summary>
- public Quaternion Rot;
- /// <summary>
- /// Translation between the two sensors. T[0] is the distance between the two cameras in meters.
- /// </summary>
- public Vector3 Trans;
- };
- /// <summary>
- /// Container for information about the current SVO recording process.
- /// </summary><remarks>
- /// Mirrors sl.RecordingState in the ZED C++ SDK. For more info, visit:
- /// https://www.stereolabs.com/developers/documentation/API/v2.5.1/structsl_1_1RecordingState.html
- /// </remarks>
- [StructLayout(LayoutKind.Sequential)]
- public struct Recording_state
- {
- /// <summary>
- /// Status of the current frame. True if recording was successful, false if frame could not be written.
- /// </summary>
- public bool status;
- /// <summary>
- /// Compression time for the current frame in milliseconds.
- /// </summary>
- public double current_compression_time;
- /// <summary>
- /// Compression ratio (% of raw size) for the current frame.
- /// </summary>
- public double current_compression_ratio;
- /// <summary>
- /// Average compression time in millisecond since beginning of recording.
- /// </summary>
- public double average_compression_time;
- /// <summary>
- /// Compression ratio (% of raw size) since recording was started.
- /// </summary>
- public double average_compression_ratio;
- }
- /// <summary>
- /// Status of the ZED's self-calibration. Since v0.9.3, self-calibration is done in the background and
- /// starts in the sl.ZEDCamera.Init or Reset functions.
- /// </summary><remarks>
- /// Mirrors SELF_CALIBRATION_STATE in the ZED C++ SDK. For more info, see:
- /// https://www.stereolabs.com/developers/documentation/API/v2.5.1/group__Video__group.html#gacce19db438a07075b7e5e22ee5845c95
- /// </remarks>
- public enum ZED_SELF_CALIBRATION_STATE
- {
- /// <summary>
- /// Self-calibration has not yet been called (no Init() called).
- /// </summary>
- SELF_CALIBRATION_NOT_CALLED,
- /// <summary>
- /// Self-calibration is currently running.
- /// </summary>
- SELF_CALIBRATION_RUNNING,
- /// <summary>
- /// Self-calibration has finished running but did not manage to get coherent values. Old Parameters are used instead.
- /// </summary>
- SELF_CALIBRATION_FAILED,
- /// <summary>
- /// Self Calibration has finished running and successfully produces coherent values.
- /// </summary>
- SELF_CALIBRATION_SUCCESS
- };
- /// <summary>
- /// Lists available depth computation modes. Each mode offers better accuracy than the
- /// mode before it, but at a performance cost.
- /// </summary><remarks>
- /// Mirrors DEPTH_MODE in the ZED C++ SDK. For more info, see:
- /// https://www.stereolabs.com/developers/documentation/API/v2.5.1/group__Depth__group.html#ga8d542017c9b012a19a15d46be9b7fa43
- /// </remarks>
- public enum DEPTH_MODE
- {
- /// <summary>
- /// Does not compute any depth map. Only rectified stereo images will be available.
- /// </summary>
- NONE,
- /// <summary>
- /// Fastest mode for depth computation.
- /// </summary>
- PERFORMANCE,
- /// <summary>
- /// Balanced quality mode. Depth map is robust in most environment and requires medium compute power.
- /// </summary>
- QUALITY,
- /// <summary>
- /// Native depth. Very accurate, but at a large performance cost.
- /// </summary>
- ULTRA,
- /// <summary>
- /// End to End Neural disparity estimation, requires AI module
- /// </summary>
- NEURAL
- };
- /// <summary>
- /// Types of Image view modes, for creating human-viewable textures.
- /// Used only in ZEDRenderingPlane as a simplified version of sl.VIEW, which has more detailed options.
- /// </summary>
- public enum VIEW_MODE
- {
- /// <summary>
- /// Dsplays regular color images.
- /// </summary>
- VIEW_IMAGE,
- /// <summary>
- /// Displays a greyscale depth map.
- /// </summary>
- VIEW_DEPTH,
- /// <summary>
- /// Displays a normal map.
- /// </summary>
- VIEW_NORMALS,
- };
- /// <summary>
- /// List of error codes in the ZED SDK.
- /// </summary><remarks>
- /// Mirrors ERROR_CODE in the ZED C++ SDK. For more info, read:
- /// https://www.stereolabs.com/developers/documentation/API/v2.5.1/group__Camera__group.html#ga4db9ee29f2ff83c71567c12f6bfbf28c
- /// </remarks>
- public enum ERROR_CODE
- {
- /// <summary>
- /// Operation was successful.
- /// </summary>
- SUCCESS,
- /// <summary>
- /// Standard, generic code for unsuccessful behavior when no other code is more appropriate.
- /// </summary>
- FAILURE,
- /// <summary>
- /// No GPU found, or CUDA capability of the device is not supported.
- /// </summary>
- NO_GPU_COMPATIBLE,
- /// <summary>
- /// Not enough GPU memory for this depth mode. Try a different mode (such as PERFORMANCE).
- /// </summary>
- NOT_ENOUGH_GPUMEM,
- /// <summary>
- /// The ZED camera is not plugged in or detected.
- /// </summary>
- CAMERA_NOT_DETECTED,
- /// <summary>
- /// The MCU that controls the sensors module has an invalid Serial Number. You can try to recover it launching the 'ZED Diagnostic' tool from the command line with the option '-r'.
- /// </summary>
- SENSORS_NOT_INITIALIZED,
- /// <summary>
- /// a ZED Mini is detected but the inertial sensor cannot be opened. (Never called for original ZED)
- /// </summary>
- SENSOR_NOT_DETECTED,
- /// <summary>
- /// For Nvidia Jetson X1 only - resolution not yet supported (USB3.0 bandwidth).
- /// </summary>
- INVALID_RESOLUTION,
- /// <summary>
- /// USB communication issues. Occurs when the camera FPS cannot be reached, due to a lot of corrupted frames.
- /// Try changing the USB port.
- /// </summary>
- LOW_USB_BANDWIDTH,
- /// <summary>
- /// ZED calibration file is not found on the host machine. Use ZED Explorer or ZED Calibration to get one.
- /// </summary>
- CALIBRATION_FILE_NOT_AVAILABLE,
- /// <summary>
- /// ZED calibration file is not valid. Try downloading the factory one or recalibrating using the ZED Calibration tool.
- /// </summary>
- INVALID_CALIBRATION_FILE,
- /// <summary>
- /// The provided SVO file is not valid.
- /// </summary>
- INVALID_SVO_FILE,
- /// <summary>
- /// An SVO recorder-related error occurred (such as not enough free storage or an invalid file path).
- /// </summary>
- SVO_RECORDING_ERROR,
- /// <summary>
- /// An SVO related error when NVIDIA based compression cannot be loaded
- /// </summary>
- SVO_UNSUPPORTED_COMPRESSION,
- /// <summary>
- /// The requested coordinate system is not available.
- /// </summary>
- INVALID_COORDINATE_SYSTEM,
- /// <summary>
- /// The firmware of the ZED is out of date. Update to the latest version.
- /// </summary>
- INVALID_FIRMWARE,
- /// <summary>
- /// An invalid parameter has been set for the function.
- /// </summary>
- INVALID_FUNCTION_PARAMETERS,
- /// <summary>
- /// In grab() only, the current call return the same frame as last call. Not a new frame.
- /// </summary>
- NOT_A_NEW_FRAME,
- /// <summary>
- /// In grab() only, a CUDA error has been detected in the process. Activate wrapperVerbose in ZEDManager.cs for more info.
- /// </summary>
- CUDA_ERROR,
- /// <summary>
- /// In grab() only, ZED SDK is not initialized. Probably a missing call to sl::Camera::open.
- /// </summary>
- CAMERA_NOT_INITIALIZED,
- /// <summary>
- /// Your NVIDIA driver is too old and not compatible with your current CUDA version.
- /// </summary>
- NVIDIA_DRIVER_OUT_OF_DATE,
- /// <summary>
- /// The function call is not valid in the current context. Could be a missing a call to sl::Camera::open.
- /// </summary>
- INVALID_FUNCTION_CALL,
- /// <summary>
- /// The SDK wasn't able to load its dependencies, the installer should be launched.
- /// </summary>
- CORRUPTED_SDK_INSTALLATION,
- /// <summary>
- /// The installed SDK is not the SDK used to compile the program.
- /// </summary>
- INCOMPATIBLE_SDK_VERSION,
- /// <summary>
- /// The given area file does not exist. Check the file path.
- /// </summary>
- INVALID_AREA_FILE,
- /// <summary>
- /// The area file does not contain enough data to be used ,or the sl::DEPTH_MODE used during the creation of the
- /// area file is different from the one currently set.
- /// </summary>
- INCOMPATIBLE_AREA_FILE,
- /// <summary>
- /// Camera failed to set up.
- /// </summary>
- CAMERA_FAILED_TO_SETUP,
- /// <summary>
- /// Your ZED cannot be opened. Try replugging it to another USB port or flipping the USB-C connector (if using ZED Mini).
- /// </summary>
- CAMERA_DETECTION_ISSUE,
- /// <summary>
- /// The Camera is already in use by another process.
- /// </summary>
- CAMERA_ALREADY_IN_USE,
- /// <summary>
- /// No GPU found or CUDA is unable to list it. Can be a driver/reboot issue.
- /// </summary>
- NO_GPU_DETECTED,
- /// <summary>
- /// Plane not found. Either no plane is detected in the scene, at the location or corresponding to the floor,
- /// or the floor plane doesn't match the prior given.
- /// </summary>
- PLANE_NOT_FOUND,
- /// <summary>
- /// The Object detection module is only compatible with the ZED 2
- /// </summary>
- MODULE_NOT_COMPATIBLE_WITH_CAMERA,
- /// <summary>
- /// The module needs the sensors to be enabled (see InitParameters::sensors_required)
- /// </summary>
- MOTION_SENSORS_REQUIRED,
- /// <summary>
- /// The module needs a newer version of CUDA
- /// </summary>
- MODULE_NOT_COMPATIBLE_WITH_CUDA_VERSION,
- /// <summary>
- /// End of ERROR_CODE
- /// </summary>
- ERROR_CODE_LAST
- };
- /// <summary>
- /// Represents the available resolution options.
- /// </summary>
- public enum RESOLUTION
- {
- /// <summary>
- /// 2208*1242. Supported frame rate: 15 FPS.
- /// </summary>
- HD2K,
- /// <summary>
- /// 1920*1080. Supported frame rates: 15, 30 FPS.
- /// </summary>
- HD1080,
- /// <summary>
- /// 1280*720. Supported frame rates: 15, 30, 60 FPS.
- /// </summary>
- HD720,
- /// <summary>
- /// 672*376. Supported frame rates: 15, 30, 60, 100 FPS.
- /// </summary>
- VGA
- };
- /// <summary>
- /// Types of compatible ZED cameras.
- /// </summary>
- public enum MODEL
- {
- /// <summary>
- /// ZED(1)
- /// </summary>
- ZED,
- /// <summary>
- /// ZED Mini.
- /// </summary>
- ZED_M,
- /// <summary>
- /// ZED2.
- /// </summary>
- ZED2,
- /// <summary>
- /// ZED2i
- /// </summary>
- ZED2i
- };
- /// <summary>
- /// Lists available sensing modes - whether to produce the original depth map (STANDARD) or one with
- /// smoothing and other effects added to fill gaps and roughness (FILL).
- /// </summary>
- public enum SENSING_MODE
- {
- /// <summary>
- /// This mode outputs the standard ZED depth map that preserves edges and depth accuracy.
- /// However, there will be missing data where a depth measurement couldn't be taken, such as from
- /// a surface being occluded from one sensor but not the other.
- /// Better for: Obstacle detection, autonomous navigation, people detection, 3D reconstruction.
- /// </summary>
- STANDARD,
- /// <summary>
- /// This mode outputs a smooth and fully dense depth map. It doesn't have gaps in the data
- /// like STANDARD where depth can't be calculated directly, but the values it fills them with
- /// is less accurate than a real measurement.
- /// Better for: AR/VR, mixed-reality capture, image post-processing.
- /// </summary>
- FILL
- };
- /// <summary>
- /// Lists available view types retrieved from the camera, used for creating human-viewable (Image-type) textures.
- /// </summary><remarks>
- /// Based on the VIEW enum in the ZED C++ SDK. For more info, see:
- /// https://www.stereolabs.com/developers/documentation/API/v2.5.1/group__Video__group.html#ga77fc7bfc159040a1e2ffb074a8ad248c
- /// </remarks>
- public enum VIEW
- {
- /// <summary>
- /// Left RGBA image. As a ZEDMat, MAT_TYPE is set to MAT_TYPE_8U_C4.
- /// </summary>
- LEFT,
- /// <summary>
- /// Right RGBA image. As a ZEDMat, MAT_TYPE is set to sl::MAT_TYPE_8U_C4.
- /// </summary>
- RIGHT,
- /// <summary>
- /// Left GRAY image. As a ZEDMat, MAT_TYPE is set to sl::MAT_TYPE_8U_C1.
- /// </summary>
- LEFT_GREY,
- /// <summary>
- /// Right GRAY image. As a ZEDMat, MAT_TYPE is set to sl::MAT_TYPE_8U_C1.
- /// </summary>
- RIGHT_GREY,
- /// <summary>
- /// Left RGBA unrectified image. As a ZEDMat, MAT_TYPE is set to sl::MAT_TYPE_8U_C4.
- /// </summary>
- LEFT_UNRECTIFIED,
- /// <summary>
- /// Right RGBA unrectified image. As a ZEDMat, MAT_TYPE is set to sl::MAT_TYPE_8U_C4.
- /// </summary>
- RIGHT_UNRECTIFIED,
- /// <summary>
- /// Left GRAY unrectified image. As a ZEDMat, MAT_TYPE is set to sl::MAT_TYPE_8U_C1.
- /// </summary>
- LEFT_UNRECTIFIED_GREY,
- /// <summary>
- /// Right GRAY unrectified image. As a ZEDMat, MAT_TYPE is set to sl::MAT_TYPE_8U_C1.
- /// </summary>
- RIGHT_UNRECTIFIED_GREY,
- /// <summary>
- /// Left and right image. Will be double the width to hold both. As a ZEDMat, MAT_TYPE is set to MAT_8U_C4.
- /// </summary>
- SIDE_BY_SIDE,
- /// <summary>
- /// Normalized depth image. As a ZEDMat, MAT_TYPE is set to sl::MAT_TYPE_8U_C4.
- /// <para>Use an Image texture for viewing only. For measurements, use a Measure type instead
- /// (ZEDCamera.RetrieveMeasure()) to preserve accuracy. </para>
- /// </summary>
- DEPTH,
- /// <summary>
- /// Normalized confidence image. As a ZEDMat, MAT_TYPE is set to MAT_8U_C4.
- /// <para>Use an Image texture for viewing only. For measurements, use a Measure type instead
- /// (ZEDCamera.RetrieveMeasure()) to preserve accuracy. </para>
- /// </summary>
- CONFIDENCE,
- /// <summary>
- /// Color rendering of the normals. As a ZEDMat, MAT_TYPE is set to MAT_8U_C4.
- /// <para>Use an Image texture for viewing only. For measurements, use a Measure type instead
- /// (ZEDCamera.RetrieveMeasure()) to preserve accuracy. </para>
- /// </summary>
- NORMALS,
- /// <summary>
- /// Color rendering of the right depth mapped on right sensor. As a ZEDMat, MAT_TYPE is set to MAT_8U_C4.
- /// <para>Use an Image texture for viewing only. For measurements, use a Measure type instead
- /// (ZEDCamera.RetrieveMeasure()) to preserve accuracy. </para>
- /// </summary>
- DEPTH_RIGHT,
- /// <summary>
- /// Color rendering of the normals mapped on right sensor. As a ZEDMat, MAT_TYPE is set to MAT_8U_C4.
- /// <para>Use an Image texture for viewing only. For measurements, use a Measure type instead
- /// (ZEDCamera.RetrieveMeasure()) to preserve accuracy. </para>
- /// </summary>
- NORMALS_RIGHT
- };
- /// <summary>
- /// Lists available camera settings for the ZED camera (contrast, hue, saturation, gain, etc.)
- /// </summary>
- public enum CAMERA_SETTINGS
- {
- /// <summary>
- /// Brightness control. Value should be between 0 and 8.
- /// </summary>
- BRIGHTNESS,
- /// <summary>
- /// Contrast control. Value should be between 0 and 8.
- /// </summary>
- CONTRAST,
- /// <summary>
- /// Hue control. Value should be between 0 and 11.
- /// </summary>
- HUE,
- /// <summary>
- /// Saturation control. Value should be between 0 and 8.
- /// </summary>
- SATURATION,
- /// <summary>
- /// Sharpness control. Value should be between 0 and 8.
- /// </summary>
- SHARPNESS,
- /// <summary>
- /// Gamma control. Value should be between 1 and 9
- /// </summary>
- GAMMA,
- /// <summary>
- /// Gain control. Value should be between 0 and 100 for manual control.
- /// If ZED_EXPOSURE is set to -1 (automatic mode), then gain will be automatic as well.
- /// </summary>
- GAIN,
- /// <summary>
- /// Exposure control. Value can be between 0 and 100.
- /// Setting to -1 enables auto exposure and auto gain.
- /// Setting to 0 disables auto exposure but doesn't change the last applied automatic values.
- /// Setting to 1-100 disables auto mode and sets exposure to the chosen value.
- /// </summary>
- EXPOSURE,
- /// <summary>
- /// Auto-exposure and auto gain. Setting this to true switches on both. Assigning a specifc value to GAIN or EXPOSURE will set this to 0.
- /// </summary>
- AEC_AGC,
- /// <summary>
- /// ROI for auto exposure/gain. ROI defines the target where the AEC/AGC will be calculated
- /// Use overloaded function for this enum
- /// </summary>
- AEC_AGC_ROI,
- /// <summary>
- /// Color temperature control. Value should be between 2800 and 6500 with a step of 100.
- /// </summary>
- WHITEBALANCE,
- /// <summary>
- /// Defines if the white balance is in automatic mode or not.
- /// </summary>
- AUTO_WHITEBALANCE,
- /// <summary>
- /// front LED status (1==enable, 0 == disable)
- /// </summary>
- LED_STATUS
- };
- /// <summary>
- /// Lists available measure types retrieved from the camera, used for creating precise measurement maps
- /// (Measure-type textures).
- /// Based on the MEASURE enum in the ZED C++ SDK. For more info, see:
- /// https://www.stereolabs.com/developers/documentation/API/v2.5.1/group__Depth__group.html#ga798a8eed10c573d759ef7e5a5bcd545d
- /// </summary>
- public enum MEASURE
- {
- /// <summary>
- /// Disparity map. As a ZEDMat, MAT_TYPE is set to MAT_32F_C1.
- /// </summary>
- DISPARITY,
- /// <summary>
- /// Depth map. As a ZEDMat, MAT_TYPE is set to MAT_32F_C1.
- /// </summary>
- DEPTH,
- /// <summary>
- /// Certainty/confidence of the disparity map. As a ZEDMat, MAT_TYPE is set to MAT_32F_C1.
- /// </summary>
- CONFIDENCE,
- /// <summary>
- /// 3D coordinates of the image points. Used for point clouds in ZEDPointCloudManager.
- /// As a ZEDMat, MAT_TYPE is set to MAT_32F_C4. The 4th channel may contain the colors.
- /// </summary>
- XYZ,
- /// <summary>
- /// 3D coordinates and color of the image. As a ZEDMat, MAT_TYPE is set to MAT_32F_C4.
- /// The 4th channel encodes 4 UCHARs for colors in R-G-B-A order.
- /// </summary>
- XYZRGBA,
- /// <summary>
- /// 3D coordinates and color of the image. As a ZEDMat, MAT_TYPE is set to MAT_32F_C4.
- /// The 4th channel encode 4 UCHARs for colors in B-G-R-A order.
- /// </summary>
- XYZBGRA,
- /// <summary>
- /// 3D coordinates and color of the image. As a ZEDMat, MAT_TYPE is set to MAT_32F_C4.
- /// The 4th channel encodes 4 UCHARs for color in A-R-G-B order.
- /// </summary>
- XYZARGB,
- /// <summary>
- /// 3D coordinates and color of the image. As a ZEDMat, MAT_TYPE is set to MAT_32F_C4.
- /// Channel 4 contains color in A-B-G-R order.
- /// </summary>
- XYZABGR,
- /// <summary>
- /// 3D coordinates and color of the image. As a ZEDMat, MAT_TYPE is set to MAT_32F_C4.
- /// The 4th channel encode 4 UCHARs for color in A-B-G-R order.
- /// </summary>
- NORMALS,
- /// <summary>
- /// Disparity map for the right sensor. As a ZEDMat, MAT_TYPE is set to MAT_32F_C1.
- /// </summary>
- DISPARITY_RIGHT,
- /// <summary>
- /// Depth map for right sensor. As a ZEDMat, MAT_TYPE is set to MAT_32F_C1.
- /// </summary>
- DEPTH_RIGHT,
- /// <summary>
- /// Point cloud for right sensor. As a ZEDMat, MAT_TYPE is set to MAT_32F_C4. Channel 4 is empty.
- /// </summary>
- XYZ_RIGHT,
- /// <summary>
- /// Colored point cloud for right sensor. As a ZEDMat, MAT_TYPE is set to MAT_32F_C4.
- /// Channel 4 contains colors in R-G-B-A order.
- /// </summary>
- XYZRGBA_RIGHT,
- /// <summary>
- /// Colored point cloud for right sensor. As a ZEDMat, MAT_TYPE is set to MAT_32F_C4.
- /// Channel 4 contains colors in B-G-R-A order.
- /// </summary>
- XYZBGRA_RIGHT,
- /// <summary>
- /// Colored point cloud for right sensor. As a ZEDMat, MAT_TYPE is set to MAT_32F_C4.
- /// Channel 4 contains colors in A-R-G-B order.
- /// </summary>
- XYZARGB_RIGHT,
- /// <summary>
- /// Colored point cloud for right sensor. As a ZEDMat, MAT_TYPE is set to MAT_32F_C4.
- /// Channel 4 contains colors in A-B-G-R order.
- /// </summary>
- XYZABGR_RIGHT,
- /// <summary>
- /// Normals vector for right view. As a ZEDMat, MAT_TYPE is set to MAT_32F_C4.
- /// Channel 4 is empty (set to 0).
- /// </summary>
- NORMALS_RIGHT,
- /// <summary>
- /// Depth map in millimeter. Each pixel contains 1 unsigned short. As a ZEDMat, MAT_TYPE is set to MAT_U16_C1.
- /// </summary>
- DEPTH_U16_MM,
- /// <summary>
- /// Depth map in millimeter for right sensor. Each pixel contains 1 unsigned short. As a ZEDMat, MAT_TYPE is set to MAT_U16_C1.
- /// </summary>
- DEPTH_U16_MM_RIGHT
- };
- /// <summary>
- /// Categories indicating when a timestamp is captured.
- /// </summary>
- public enum TIME_REFERENCE
- {
- /// <summary>
- /// Timestamp from when the image was received over USB from the camera, defined
- /// by when the entire image was available in memory.
- /// </summary>
- IMAGE,
- /// <summary>
- /// Timestamp from when the relevant function was called.
- /// </summary>
- CURRENT
- };
- /// <summary>
- /// Reference frame (world or camera) for tracking and depth sensing.
- /// </summary>
- public enum REFERENCE_FRAME
- {
- /// <summary>
- /// Matrix contains the total displacement from the world origin/the first tracked point.
- /// </summary>
- WORLD,
- /// <summary>
- /// Matrix contains the displacement from the previous camera position to the current one.
- /// </summary>
- CAMERA
- };
- /// <summary>
- /// Possible states of the ZED's Tracking system.
- /// </summary>
- public enum TRACKING_STATE
- {
- /// <summary>
- /// Tracking is searching for a match from the database to relocate to a previously known position.
- /// </summary>
- TRACKING_SEARCH,
- /// <summary>
- /// Tracking is operating normally; tracking data should be correct.
- /// </summary>
- TRACKING_OK,
- /// <summary>
- /// Tracking is not enabled.
- /// </summary>
- TRACKING_OFF,
- /// <summary>
- /// This is the last searching state of the track, the track will be deleted in the next retreiveObject
- /// </summary>
- TRACKING_TERMINATE
- }
- /// <summary>
- /// SVO compression modes.
- /// </summary>
- public enum SVO_COMPRESSION_MODE
- {
- /// <summary>
- /// Lossless compression based on png/zstd. Average size = 42% of RAW.
- /// </summary>
- LOSSLESS_BASED,
- /// <summary>
- /// H264(AVCHD) GPU based compression : avg size = 1% (of RAW). Requires a NVIDIA GPU
- /// </summary>
- H264_BASED,
- /// <summary>
- /// H265(HEVC) GPU based compression: avg size = 1% (of RAW). Requires a NVIDIA GPU, Pascal architecture or newer
- /// </summary>
- H265_BASED,
- /// <summary>
- /// H264 Lossless GPU/Hardware based compression: avg size = 25% (of RAW). Provides a SSIM/PSNR result (vs RAW) >= 99.9%. Requires a NVIDIA GPU
- /// </summary>
- H264_LOSSLESS_BASED,
- /// <summary>
- /// H265 Lossless GPU/Hardware based compression: avg size = 25% (of RAW). Provides a SSIM/PSNR result (vs RAW) >= 99.9%. Requires a NVIDIA GPU
- /// </summary>
- H265_LOSSLESS_BASED,
- }
- /// <summary>
- /// Streaming codecs
- /// </summary>
- public enum STREAMING_CODEC
- {
- /// <summary>
- /// AVCHD Based compression (H264)
- /// </summary>
- AVCHD_BASED,
- /// <summary>
- /// HEVC Based compression (H265)
- /// </summary>
- HEVC_BASED
- }
- /// <summary>
- /// Spatial Mapping type (default is mesh)
- /// </summary>
- public enum SPATIAL_MAP_TYPE
- {
- /// <summary>
- /// Represent a surface with faces, 3D points are linked by edges, no color information
- /// </summary>
- MESH,
- /// <summary>
- /// Geometry is represented by a set of 3D colored points.
- /// </summary>
- FUSED_POINT_CLOUD
- };
- /// <summary>
- /// Mesh formats that can be saved/loaded with spatial mapping.
- /// </summary>
- public enum MESH_FILE_FORMAT
- {
- /// <summary>
- /// Contains only vertices and faces.
- /// </summary>
- PLY,
- /// <summary>
- /// Contains only vertices and faces, encoded in binary.
- /// </summary>
- BIN,
- /// <summary>
- /// Contains vertices, normals, faces, and texture information (if possible).
- /// </summary>
- OBJ
- }
- /// <summary>
- /// Presets for filtering meshes scannedw ith spatial mapping. Higher values reduce total face count by more.
- /// </summary>
- public enum FILTER
- {
- /// <summary>
- /// Soft decimation and smoothing.
- /// </summary>
- LOW,
- /// <summary>
- /// Decimate the number of faces and apply a soft smooth.
- /// </summary>
- MEDIUM,
- /// <summary>
- /// Drastically reduce the number of faces.
- /// </summary>
- HIGH,
- }
- /// <summary>
- /// Possible states of the ZED's Spatial Mapping system.
- /// </summary>
- public enum SPATIAL_MAPPING_STATE
- {
- /// <summary>
- /// Spatial mapping is initializing.
- /// </summary>
- SPATIAL_MAPPING_STATE_INITIALIZING,
- /// <summary>
- /// Depth and tracking data were correctly integrated into the fusion algorithm.
- /// </summary>
- SPATIAL_MAPPING_STATE_OK,
- /// <summary>
- /// Maximum memory dedicated to scanning has been reached; the mesh will no longer be updated.
- /// </summary>
- SPATIAL_MAPPING_STATE_NOT_ENOUGH_MEMORY,
- /// <summary>
- /// EnableSpatialMapping() wasn't called (or the scanning was stopped and not relaunched).
- /// </summary>
- SPATIAL_MAPPING_STATE_NOT_ENABLED,
- /// <summary>
- /// Effective FPS is too low to give proper results for spatial mapping.
- /// Consider using performance-friendly parameters (DEPTH_MODE_PERFORMANCE, VGA or HD720 camera resolution,
- /// and LOW spatial mapping resolution).
- /// </summary>
- SPATIAL_MAPPING_STATE_FPS_TOO_LOW
- }
- /// <summary>
- /// Units used by the SDK for measurements and tracking. METER is best to stay consistent with Unity.
- /// </summary>
- public enum UNIT
- {
- /// <summary>
- /// International System, 1/1000 meters.
- /// </summary>
- MILLIMETER,
- /// <summary>
- /// International System, 1/100 meters.
- /// </summary>
- CENTIMETER,
- /// <summary>
- /// International System, 1/1 meters.
- /// </summary>
- METER,
- /// <summary>
- /// Imperial Unit, 1/12 feet.
- /// </summary>
- INCH,
- /// <summary>
- /// Imperial Unit, 1/1 feet.
- /// </summary>
- FOOT
- }
- /// <summary>
- /// Struct containing all parameters passed to the SDK when initializing the ZED.
- /// These parameters will be fixed for the whole execution life time of the camera.
- /// </summary><remarks>For more details, see the InitParameters class in the SDK API documentation:
- /// https://www.stereolabs.com/developers/documentation/API/v2.5.1/structsl_1_1InitParameters.html </remarks>
- /// </summary>
- public class InitParameters
- {
- public sl.INPUT_TYPE inputType;
- /// <summary>
- /// Resolution the ZED will be set to.
- /// </summary>
- public sl.RESOLUTION resolution;
- /// <summary>
- /// Requested FPS for this resolution. Setting it to 0 will choose the default FPS for this resolution.
- /// </summary>
- public int cameraFPS;
- /// <summary>
- /// ID for identifying which of multiple connected ZEDs to use.
- /// </summary>
- public int cameraDeviceID;
- /// <summary>
- /// Path to a recorded SVO file to play, including filename.
- /// </summary>
- public string pathSVO = "";
- /// <summary>
- /// In SVO playback, this mode simulates a live camera and consequently skipped frames if the computation framerate is too slow.
- /// </summary>
- public bool svoRealTimeMode;
- /// <summary>
- /// Define a unit for all metric values (depth, point clouds, tracking, meshes, etc.) Meters are recommended for Unity.
- /// </summary>
- public UNIT coordinateUnit;
- /// <summary>
- /// This defines the order and the direction of the axis of the coordinate system.
- /// LEFT_HANDED_Y_UP is recommended to match Unity's coordinates.
- /// </summary>
- public COORDINATE_SYSTEM coordinateSystem;
- /// <summary>
- /// Quality level of depth calculations. Higher settings improve accuracy but cost performance.
- /// </summary>
- public sl.DEPTH_MODE depthMode;
- /// <summary>
- /// Minimum distance from the camera from which depth will be computed, in the defined coordinateUnit.
- /// </summary>
- public float depthMinimumDistance;
- /// <summary>
- /// When estimating the depth, the SDK uses this upper limit to turn higher values into \ref TOO_FAR ones.
- /// The current maximum distance that can be computed in the defined \ref UNIT.
- /// Changing this value has no impact on performance and doesn't affect the positional tracking nor the spatial mapping. (Only the depth, point cloud, normals)
- /// </summary>
- public float depthMaximumDistance;
- /// <summary>
- /// Defines if images are horizontally flipped.
- /// </summary>
- public int cameraImageFlip;
- /// <summary>
- /// Defines if measures relative to the right sensor should be computed (needed for MEASURE_<XXX>_RIGHT).
- /// </summary>
- public bool enableRightSideMeasure;
- /// <summary>
- /// True to disable self-calibration and use the optional calibration parameters without optimizing them.
- /// False is recommended, so that calibration parameters can be optimized.
- /// </summary>
- public bool cameraDisableSelfCalib;
- /// <summary>
- /// True for the SDK to provide text feedback.
- /// </summary>
- public int sdkVerbose;
- /// <summary>
- /// ID of the graphics card on which the ZED's computations will be performed.
- /// </summary>
- public int sdkGPUId;
- /// <summary>
- /// If set to verbose, the filename of the log file into which the SDK will store its text output.
- /// </summary>
- public string sdkVerboseLogFile = "";
- /// <summary>
- /// True to stabilize the depth map. Recommended.
- /// </summary>
- public bool depthStabilization;
- /// <summary>
- /// Optional path for searching configuration (calibration) file SNxxxx.conf. (introduced in ZED SDK 2.6)
- /// </summary>
- public string optionalSettingsPath = "";
- /// <summary>
- /// True to stabilize the depth map. Recommended.
- /// </summary>
- public bool sensorsRequired;
- /// <summary>
- /// Path to a recorded SVO file to play, including filename.
- /// </summary>
- public string ipStream = "";
- /// <summary>
- /// Path to a recorded SVO file to play, including filename.
- /// </summary>
- public ushort portStream = 30000;
- /// <summary>
- /// Whether to enable improved color/gamma curves added in ZED SDK 3.0.
- /// </summary>
- public bool enableImageEnhancement = true;
- /// <summary>
- /// Set an optional file path where the SDK can find a file containing the calibration information of the camera computed by OpenCV.
- /// <remarks> Using this will disable the factory calibration of the camera. </remarks>
- /// <warning> Erroneous calibration values can lead to poor SDK modules accuracy. </warning>
- /// </summary>
- public string optionalOpencvCalibrationFile = "";
- /// <summary>
- /// Define a timeout in seconds after which an error is reported if the \ref open() command fails.
- /// Set to '-1' to try to open the camera endlessly without returning error in case of failure.
- /// Set to '0' to return error in case of failure at the first attempt.
- /// This parameter only impacts the LIVE mode.
- /// </summary>
- public float openTimeoutSec;
- /// <summary>
- /// Constructor. Sets default initialization parameters recommended for Unity.
- /// </summary>
- public InitParameters()
- {
- this.inputType = sl.INPUT_TYPE.INPUT_TYPE_USB;
- this.resolution = RESOLUTION.HD720;
- this.cameraFPS = 60;
- this.cameraDeviceID = 0;
- this.pathSVO = "";
- this.svoRealTimeMode = false;
- this.coordinateUnit = UNIT.METER;
- this.coordinateSystem = COORDINATE_SYSTEM.LEFT_HANDED_Y_UP;
- this.depthMode = DEPTH_MODE.PERFORMANCE;
- this.depthMinimumDistance = -1;
- this.depthMaximumDistance = -1;
- this.cameraImageFlip = 2;
- this.cameraDisableSelfCalib = false;
- this.sdkVerbose = 0;
- this.sdkGPUId = -1;
- this.sdkVerboseLogFile = "";
- this.enableRightSideMeasure = false;
- this.depthStabilization = true;
- this.optionalSettingsPath = "";
- this.sensorsRequired = false;
- this.ipStream = "";
- this.portStream = 30000;
- this.enableImageEnhancement = true;
- this.optionalOpencvCalibrationFile = "";
- this.openTimeoutSec = 5.0f;
- }
- }
- /// <summary>
- /// List of available coordinate systems. Left-Handed, Y Up is recommended to stay consistent with Unity.
- /// consistent with Unity.
- /// </summary>
- public enum COORDINATE_SYSTEM
- {
- /// <summary>
- /// Standard coordinates system used in computer vision.
- /// Used in OpenCV. See: http://docs.opencv.org/2.4/modules/calib3d/doc/camera_calibration_and_3d_reconstruction.html
- /// </summary>
- IMAGE,
- /// <summary>
- /// Left-Handed with Y up and Z forward. Recommended. Used in Unity with DirectX.
- /// </summary>
- LEFT_HANDED_Y_UP,
- /// <summary>
- /// Right-Handed with Y pointing up and Z backward. Used in OpenGL.
- /// </summary>
- RIGHT_HANDED_Y_UP,
- /// <summary>
- /// Right-Handed with Z pointing up and Y forward. Used in 3DSMax.
- /// </summary>
- RIGHT_HANDED_Z_UP,
- /// <summary>
- /// Left-Handed with Z axis pointing up and X forward. Used in Unreal Engine.
- /// </summary>
- LEFT_HANDED_Z_UP
- }
- /// <summary>
- /// Possible states of the ZED's spatial memory area export, for saving 3D features used
- /// by the tracking system to relocalize the camera. This is used when saving a mesh generated
- /// by spatial mapping when Save Mesh is enabled - a .area file is saved as well.
- /// </summary>
- public enum AREA_EXPORT_STATE
- {
- /// <summary>
- /// Spatial memory file has been successfully created.
- /// </summary>
- AREA_EXPORT_STATE_SUCCESS,
- /// <summary>
- /// Spatial memory file is currently being written to.
- /// </summary>
- AREA_EXPORT_STATE_RUNNING,
- /// <summary>
- /// Spatial memory file export has not been called.
- /// </summary>
- AREA_EXPORT_STATE_NOT_STARTED,
- /// <summary>
- /// Spatial memory contains no data; the file is empty.
- /// </summary>
- AREA_EXPORT_STATE_FILE_EMPTY,
- /// <summary>
- /// Spatial memory file has not been written to because of a bad file name.
- /// </summary>
- AREA_EXPORT_STATE_FILE_ERROR,
- /// <summary>
- /// Spatial memory has been disabled, so no file can be created.
- /// </summary>
- AREA_EXPORT_STATE_SPATIAL_MEMORY_DISABLED
- };
- /// <summary>
- /// Runtime parameters used by the ZEDCamera.Grab() function, and its Camera::grab() counterpart in the SDK.
- /// </summary>
- [StructLayout(LayoutKind.Sequential)]
- public struct RuntimeParameters {
- /// <summary>
- /// Defines the algorithm used for depth map computation, more info : \ref SENSING_MODE definition.
- /// </summary>
- public sl.SENSING_MODE sensingMode;
- /// <summary>
- /// Provides 3D measures (point cloud and normals) in the desired reference frame (default is REFERENCE_FRAME_CAMERA).
- /// </summary>
- public sl.REFERENCE_FRAME measure3DReferenceFrame;
- /// <summary>
- /// Defines whether the depth map should be computed.
- /// </summary>
- [MarshalAs(UnmanagedType.U1)]
- public bool enableDepth;
- /// <summary>
- /// Defines the confidence threshold for the depth. Based on stereo matching score.
- /// </summary>
- public int confidenceThreshold;
- /// <summary>
- /// Defines texture confidence threshold for the depth. Based on textureness confidence.
- /// </summary>
- public int textureConfidenceThreshold;
- /// <summary>
- /// Defines if the saturated area (Luminance>=255) must be removed from depth map estimation
- /// </summary>
- public bool removeSaturatedAreas;
- }
- /// <summary>
- ///brief Lists available compression modes for SVO recording.
- /// </summary>
- public enum FLIP_MODE
- {
- OFF = 0, /// default behavior.
- ON = 1, /// Images and camera sensors data are flipped, useful when your camera is mounted upside down.
- AUTO = 2, /// in live mode: use the camera orientation (if an IMU is available) to set the flip mode, in SVO mode, read the state of this enum when recorded
- };
- /// <summary>
- /// Part of the ZED (left/right sensor, center) that's considered its center for tracking purposes.
- /// </summary>
- public enum TRACKING_FRAME
- {
- /// <summary>
- /// Camera's center is at the left sensor.
- /// </summary>
- LEFT_EYE,
- /// <summary>
- /// Camera's center is in the camera's physical center, between the sensors.
- /// </summary>
- CENTER_EYE,
- /// <summary>
- /// Camera's center is at the right sensor.
- /// </summary>
- RIGHT_EYE
- };
- /// <summary>
- /// Types of USB device brands.
- /// </summary>
- public enum USB_DEVICE
- {
- /// <summary>
- /// Oculus device, eg. Oculus Rift VR Headset.
- /// </summary>
- USB_DEVICE_OCULUS,
- /// <summary>
- /// HTC device, eg. HTC Vive.
- /// </summary>
- USB_DEVICE_HTC,
- /// <summary>
- /// Stereolabs device, eg. ZED/ZED Mini.
- /// </summary>
- USB_DEVICE_STEREOLABS
- };
- ////////////////////////////////////////////////////////////////////////////////////////////////////////
- //////////////////////////////////////// Object Detection /////////////////////////////////////////////
- ////////////////////////////////////////////////////////////////////////////////////////////////////////
- /// <summary>
- /// sets batch trajectory parameters
- /// The default constructor sets all parameters to their default settings.
- /// Parameters can be user adjusted.
- /// </summary>
- [StructLayout(LayoutKind.Sequential)]
- public struct BatchParameters
- {
- /// <summary>
- /// Defines if the Batch option in the object detection module is enabled. Batch queueing system provides:
- /// - Deep-Learning based re-identification
- /// - Trajectory smoothing and filtering
- /// </summary>
- /// <remarks>
- /// To activate this option, enable must be set to true.
- /// </remarks>
- [MarshalAs(UnmanagedType.U1)]
- public bool enable;
- /// <summary>
- /// Max retention time in seconds of a detected object. After this time, the same object will mostly have a different ID.
- /// </summary>
- public float idRetentionTime;
- /// <summary>
- /// Trajectories will be output in batch with the desired latency in seconds.
- /// During this waiting time, re-identification of objects is done in the background.
- /// Specifying a short latency will limit the search (falling in timeout) for previously seen object IDs but will be closer to real time output.
- /// Specifying a long latency will reduce the change of timeout in Re-ID but increase difference with live output.
- /// </summary>
- public float latency;
- }
- /// <summary>
- /// Contains AI model status.
- /// </summary>
- [StructLayout(LayoutKind.Sequential)]
- public struct AI_Model_status
- {
- /// <summary>
- /// the model file is currently present on the host.
- /// </summary>
- [MarshalAs(UnmanagedType.U1)]
- public bool downloaded;
- /// <summary>
- /// an engine file with the expected architecure is found.
- /// </summary>
- [MarshalAs(UnmanagedType.U1)]
- public bool optimized;
- };
- /// <summary>
- /// Sets the object detection parameters.
- /// </summary>
- [StructLayout(LayoutKind.Sequential)]
- public struct dll_ObjectDetectionParameters
- {
- /// <summary>
- /// Defines if the object detection is synchronized to the image or runs in a separate thread.
- /// </summary>
- [MarshalAs(UnmanagedType.U1)]
- public bool imageSync;
- /// <summary>
- /// Defines if the object detection will track objects across multiple images, instead of an image-by-image basis.
- /// </summary>
- [MarshalAs(UnmanagedType.U1)]
- public bool enableObjectTracking;
- /// <summary>
- /// Defines if the SDK will calculate 2D masks for each object. Requires more performance, so don't enable if you don't need these masks.
- /// </summary>
- [MarshalAs(UnmanagedType.U1)]
- public bool enable2DMask;
- /// <summary>
- /// Defines the AI model used for detection
- /// </summary>
- public sl.DETECTION_MODEL detectionModel;
- /// <summary>
- /// Defines if the body fitting will be applied
- /// </summary>
- [MarshalAs(UnmanagedType.U1)]
- public bool enableBodyFitting;
- /// <summary>
- /// Body Format. BODY_FORMAT.POSE_34 automatically enables body fitting.
- /// </summary>
- public sl.BODY_FORMAT bodyFormat;
- /// <summary>
- /// Defines a upper depth range for detections.
- /// Defined in UNIT set at sl.Camera.Open.
- /// Default value is set to sl.Initparameters.depthMaximumDistance (can not be higher).
- /// </summary>
- public float maxRange;
- /// <summary>
- /// Batching system parameters.
- /// Batching system(introduced in 3.5) performs short-term re-identification with deep learning and trajectories filtering.
- /// BatchParameters.enable need to be true to use this feature (by default disabled)
- /// </summary>
- public BatchParameters batchParameters;
- /**
- \brief Defines the filtering mode that should be applied to raw detections.
- */
- public OBJECT_FILTERING_MODE filteringMode;
- };
- [StructLayout(LayoutKind.Sequential)]
- public struct dll_ObjectDetectionRuntimeParameters
- {
- /// <summary>
- /// The detection confidence threshold between 1 and 99.
- /// A confidence of 1 means a low threshold, more uncertain objects and 99 very few but very precise objects.
- /// Ex: If set to 80, then the SDK must be at least 80% sure that a given object exists before reporting it in the list of detected objects.
- /// If the scene contains a lot of objects, increasing the confidence can slightly speed up the process, since every object instance is tracked.
- /// </summary>
- public float detectionConfidenceThreshold;
- /// <summary>
- ///
- /// </summary>
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = (int)sl.OBJECT_CLASS.LAST)]
- public int[] objectClassFilter;
- /// <summary>
- ///
- /// </summary>
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = (int)sl.OBJECT_CLASS.LAST)]
- public int[] object_confidence_threshold;
- };
- /// <summary>
- /// Lists of supported skeleton body model
- /// </summary>
- public enum BODY_FORMAT
- {
- POSE_18,
- POSE_34,
- };
- /// <summary>
- /// Object data structure directly from the SDK. Represents a single object detection.
- /// See DetectedObject for an abstracted version with helper functions that make this data easier to use in Unity.
- /// </summary>
- [StructLayout(LayoutKind.Sequential)]
- public struct ObjectDataSDK
- {
- /// <summary>
- /// Object identification number, used as a reference when tracking the object through the frames.
- /// </summary>
- public int id;
- /// <summary>
- ///Unique ID to help identify and track AI detections. Can be either generated externally, or using \ref ZEDCamera.generateUniqueId() or left empty
- /// </summary>
- [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 37)]
- public string uniqueObjectId;
- /// <summary>
- /// Object label, forwarded from \ref CustomBoxObjects when using DETECTION_MODEL.CUSTOM_BOX_OBJECTS
- /// </summary>
- public int rawLabel;
- /// <summary>
- /// Object category. Identify the object type.
- /// </summary>
- public sl.OBJECT_CLASS objectClass;
- public sl.OBJECT_SUBCLASS objectSubClass;
- public sl.OBJECT_TRACK_STATE objectTrackingState;
- public sl.OBJECT_ACTION_STATE actionState;
- public float confidence;
- public System.IntPtr mask;
- /// <summary>
- /// Image data.
- /// Note that Y in these values is relative from the top of the image, whereas the opposite is true
- /// in most related Unity functions. If using this raw value, subtract Y from the
- /// image height to get the height relative to the bottom.
- /// </summary>
- /// 0 ------- 1
- /// | obj |
- /// 3-------- 2
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)]
- public Vector2[] imageBoundingBox;
- /// <summary>
- /// 3D space data (Camera Frame since this is what we used in Unity)
- /// </summary>
- public Vector3 rootWorldPosition; //object root position
- public Vector3 headWorldPosition; //object head position (only for HUMAN detectionModel)
- public Vector3 rootWorldVelocity; //object root velocity
- /// <summary>
- /// The 3D space bounding box. given as array of vertices
- /// </summary>
- /// 1 ---------2
- /// /| /|
- /// 0 |--------3 |
- /// | | | |
- /// | 5--------|-6
- /// |/ |/
- /// 4 ---------7
- ///
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = 8)]
- public Vector3[] worldBoundingBox; // 3D Bounding Box of object
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = 8)]
- public Vector3[] headBoundingBox;// 3D Bounding Box of head (only for HUMAN detectionModel)
- /// <summary>
- /// The 2D position of skeleton joints
- /// </summary>
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = 34)]
- public Vector2[] skeletonJointPosition2D;// 2D position of the joints of the skeleton
- /// <summary>
- /// The 3D position of skeleton joints
- /// </summary>
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = 34)]
- public Vector3[] skeletonJointPosition;// 3D position of the joints of the skeleton
- // Full covariance matrix for position (3x3). Only 6 values are necessary
- // [p0, p1, p2]
- // [p1, p3, p4]
- // [p2, p4, p5]
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = 6)]
- public float[] positionCovariance;// covariance matrix of the 3d position, represented by its upper triangular matrix value
- /// <summary>
- /// Per keypoint detection confidence, can not be lower than the ObjectDetectionRuntimeParameters.detection_confidence_threshold.
- /// Not available with DETECTION_MODEL.MULTI_CLASS_BOX.
- /// in some cases, eg. body partially out of the image or missing depth data, some keypoint can not be detected, they will have non finite values.
- /// </summary>
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = 34)]
- public float[] keypointConfidence;
- /// <summary>
- /// Global position per joint in the coordinate frame of the requested skeleton format.
- /// </summary>
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = 34)]
- public Vector3[] localPositionPerJoint;
- /// <summary>
- /// Local orientation per joint in the coordinate frame of the requested skeleton format.
- /// The orientation is represented by a quaternion.
- /// </summary>
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = 34)]
- public Quaternion[] localOrientationPerJoint;
- /// <summary>
- /// Global root rotation.
- /// </summary>
- public Quaternion globalRootOrientation;
- };
- /// <summary>
- /// Container to store the externally detected objects. The objects can be ingested using IngestCustomBoxObjects() function to extract 3D information and tracking over time.
- /// </summary>
- [StructLayout(LayoutKind.Sequential)]
- public struct CustomBoxObjectData
- {
- /// <summary>
- ///Unique ID to help identify and track AI detections. Can be either generated externally, or using \ref ZEDCamera.generateUniqueId() or left empty
- /// </summary>
- [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 37)]
- public string uniqueObjectID;
- /// <summary>
- /// 2D bounding box represented as four 2D points starting at the top left corner and rotation clockwise.
- /// </summary>
- /// 0 ------- 1
- /// | obj |
- /// 3-------- 2
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = 4)]
- public Vector2[] boundingBox2D;
- /// <summary>
- /// Object label, this information is passed-through and can be used to improve object tracking
- /// </summary>
- public int label;
- /// <summary>
- /// Detection confidence. Should be [0-1]. It can be used to improve the object tracking
- /// </summary>
- public float probability;
- /// <summary>
- /// Provide hypothesis about the object movements(degrees of freedom) to improve the object tracking
- /// true: means 2 DoF projected alongside the floor plane, the default for object standing on the ground such as person, vehicle, etc
- /// false : 6 DoF full 3D movements are allowed
- /// </summary>
- [MarshalAs(UnmanagedType.U1)]
- public bool isGrounded;
- }
- /// <summary>
- /// Object Scene data directly from the ZED SDK. Represents all detections given during a single image frame.
- /// See DetectionFrame for an abstracted version with helper functions that make this data easier to use in Unity.
- /// Contains the number of object in the scene and the objectData structure for each object.
- /// Since the data is transmitted from C++ to C#, the size of the structure must be constant. Therefore, there is a limitation of 200 (MAX_OBJECT constant) objects in the image.
- /// <c> This number cannot be changed.<c>
- /// </summary>
- [StructLayout(LayoutKind.Sequential)]
- public struct ObjectsFrameSDK
- {
- /// <summary>
- /// How many objects were detected this frame. Use this to iterate through the top of objectData; objects with indexes greater than numObject are empty.
- /// </summary>
- public int numObject;
- /// <summary>
- /// Timestamp of the image where these objects were detected.
- /// </summary>
- public ulong timestamp;
- /// <summary>
- /// Defines if the object frame is new (new timestamp)
- /// </summary>
- public int isNew;
- /// <summary>
- /// Defines if the object is tracked
- /// </summary>
- public int isTracked;
- /// <summary>
- /// Current detection model used.
- /// </summary>
- public sl.DETECTION_MODEL detectionModel;
- /// <summary>
- /// Array of objects
- /// </summary>
- [MarshalAs(UnmanagedType.ByValArray, SizeConst = (int)(Constant.MAX_OBJECTS))]
- public ObjectDataSDK[] objectData;
- };
- /// <summary>
- /// Lists available object class
- /// </summary>
- public enum OBJECT_CLASS
- {
- PERSON = 0,
- VEHICLE = 1,
- BAG = 2,
- ANIMAL = 3,
- ELECTRONICS = 4,
- FRUIT_VEGETABLE = 5,
- SPORT = 6,
- LAST = 7
- };
- /// <summary>
- /// Lists available object subclass.
- /// </summary>
- public enum OBJECT_SUBCLASS
- {
- PERSON = 0,
- // VEHICLES
- BICYCLE = 1,
- CAR = 2,
- MOTORBIKE = 3,
- BUS = 4,
- TRUCK = 5,
- BOAT = 6,
- // BAGS
- BACKPACK = 7,
- HANDBAG = 8,
- SUITCASE = 9,
- // ANIMALS
- BIRD = 10,
- CAT = 11,
- DOG = 12,
- HORSE = 13,
- SHEEP = 14,
- COW = 15,
- // ELECTRONICS
- CELLPHONE = 16,
- LAPTOP = 17,
- // FRUITS/VEGETABLES
- BANANA = 18,
- APPLE = 19,
- ORANGE = 20,
- CARROT = 21,
- PERSON_HEAD = 22,
- SPORTSBALL = 23,
- LAST = 24
- };
- /// <summary>
- /// Tracking state of an individual object.
- /// </summary>
- public enum OBJECT_TRACK_STATE
- {
- OFF, /**< The tracking is not yet initialized, the object ID is not usable */
- OK, /**< The object is tracked */
- SEARCHING,/**< The object couldn't be detected in the image and is potentially occluded, the trajectory is estimated */
- TERMINATE/**< This is the last searching state of the track, the track will be deleted in the next retreiveObject */
- };
- public enum OBJECT_ACTION_STATE
- {
- IDLE = 0, /**< The object is staying static. */
- MOVING = 1, /**< The object is moving. */
- LAST = 2
- };
- /// <summary>
- /// List available models for detection
- /// </summary>
- public enum DETECTION_MODEL {
- /// <summary>
- /// Any objects, bounding box based.
- /// </summary>
- MULTI_CLASS_BOX,
- /// <summary>
- /// Any objects, bounding box based.
- /// </summary>
- MULTI_CLASS_BOX_ACCURATE,
- /// <summary>
- /// Keypoints based, specific to human skeleton, real time performance even on Jetson or low end GPU cards.
- /// </summary>
- HUMAN_BODY_FAST,
- /// <summary>
- /// Keypoints based, specific to human skeleton, state of the art accuracy, requires powerful GPU.
- /// </summary>
- HUMAN_BODY_ACCURATE,
- /// <summary>
- /// Any objects, bounding box based.
- /// </summary>
- MULTI_CLASS_BOX_MEDIUM,
- /// <summary>
- /// Keypoints based, specific to human skeleton, real time performance even on Jetson or low end GPU cards.
- /// </summary>
- HUMAN_BODY_MEDIUM,
- /// <summary>
- /// Bounding Box detector specialized in person heads, particulary well suited for crowded environement, the person localization is also improved
- /// </summary>
- PERSON_HEAD_BOX,
- /// <summary>
- /// For external inference, using your own custom model and/or frameworks. This mode disable the internal inference engine, the 2D bounding box detection must be provided
- /// </summary>
- CUSTOM_BOX_OBJECTS,
- LAST
- };
- /// <summary>
- /// Lists of supported bounding box preprocessing
- /// </summary>
- public enum OBJECT_FILTERING_MODE
- {
- /// <summary>
- /// SDK will not apply any preprocessing to the detected objects
- /// </summary>
- NONE,
- /// <summary>
- /// SDK will remove objects that are in the same 3D position as an already tracked object (independant of class ID). Default value
- /// </summary>
- NMS3D,
- /// <summary>
- /// SDK will remove objects that are in the same 3D position as an already tracked object of the same class ID
- /// </summary>
- NMS3D_PER_CLASS
- };
- public enum AI_MODELS
- {
- /// <summary>
- /// related to sl.DETECTION_MODEL.MULTI_CLASS_BOX
- /// </summary>
- MULTI_CLASS_DETECTION,
- /// <summary>
- /// related to sl.DETECTION_MODEL.MULTI_CLASS_BOX_MEDIUM
- /// </summary>
- MULTI_CLASS_MEDIUM_DETECTION,
- /// <summary>
- /// related to sl.DETECTION_MODEL.MULTI_CLASS_BOX_ACCURATE
- /// </summary>
- MULTI_CLASS_ACCURATE_DETECTION,
- /// <summary>
- /// related to sl.DETECTION_MODEL.HUMAN_BODY_FAST
- /// </summary>
- HUMAN_BODY_FAST_DETECTION,
- /// <summary>
- /// related to sl.DETECTION_MODEL.HUMAN_BODY_MEDIUM
- /// </summary>
- HUMAN_BODY_MEDIUM_DETECTION,
- /// <summary>
- /// related to sl.DETECTION_MODEL.HUMAN_BODY_ACCURATE
- /// </summary>
- HUMAN_BODY_ACCURATE_DETECTION, //
- /// <summary>
- /// related to sl.DETECTION_MODEL.PERSON_HEAD
- /// </summary>
- PERSON_HEAD_DETECTION,
- /// <summary>
- /// related to sl.BatchParameters.enable
- /// </summary>
- REID_ASSOCIATION, // related to
- /// <summary>
- /// related to sl.DETECTION_MODEL.NEURAL
- /// </summary>
- NEURAL_DEPTH,
- LAST
- };
- /// <summary>
- /// semantic and order of human body keypoints.
- /// </summary>
- public enum BODY_PARTS {
- NOSE = 0,
- NECK = 1,
- RIGHT_SHOULDER = 2,
- RIGHT_ELBOW= 3,
- RIGHT_WRIST = 4,
- LEFT_SHOULDER = 5,
- LEFT_ELBOW = 6,
- LEFT_WRIST = 7,
- RIGHT_HIP = 8,
- RIGHT_KNEE = 9,
- RIGHT_ANKLE = 10,
- LEFT_HIP = 11,
- LEFT_KNEE = 12,
- LEFT_ANKLE = 13,
- RIGHT_EYE = 14,
- LEFT_EYE = 15,
- RIGHT_EAR = 16,
- LEFT_EAR = 17,
- LAST = 18
- };
- /// <summary>
- /// Contains batched data of a detected object
- /// </summary>
- /// <summary>
- /// Contains batched data of a detected object
- /// </summary>
- public class ObjectsBatch
- {
- /// <summary>
- /// How many data were stored. Use this to iterate through the top of position/velocity/bounding_box/...; objects with indexes greater than numData are empty.
- /// </summary>
- public int numData = 0;
- /// <summary>
- /// The trajectory id
- /// </summary>
- public int id = 0;
- /// <summary>
- /// Object Category. Identity the object type
- /// </summary>
- public OBJECT_CLASS label = OBJECT_CLASS.LAST;
- /// <summary>
- /// Object subclass
- /// </summary>
- public OBJECT_SUBCLASS sublabel = OBJECT_SUBCLASS.LAST;
- /// <summary>
- /// Defines the object tracking state
- /// </summary>
- public TRACKING_STATE trackingState = TRACKING_STATE.TRACKING_TERMINATE;
- /// <summary>
- /// A sample of 3d position
- /// </summary>
- public Vector3[] positions = new Vector3[(int)Constant.MAX_BATCH_SIZE];
- /// <summary>
- /// a sample of the associated position covariance
- /// </summary>
- public float[,] positionCovariances = new float[(int)Constant.MAX_BATCH_SIZE, 6];
- /// <summary>
- /// A sample of 3d velocity
- /// </summary>
- public Vector3[] velocities = new Vector3[(int)Constant.MAX_BATCH_SIZE];
- /// <summary>
- /// The associated position timestamp
- /// </summary>
- public ulong[] timestamps = new ulong[(int)Constant.MAX_BATCH_SIZE];
- /// <summary>
- /// A sample of 3d bounding boxes
- /// </summary>
- public Vector3[,] boundingBoxes = new Vector3[(int)Constant.MAX_BATCH_SIZE, 8];
- /// <summary>
- /// 2D bounding box of the person represented as four 2D points starting at the top left corner and rotation clockwise.
- /// Expressed in pixels on the original image resolution, [0, 0] is the top left corner.
- /// A ------ B
- /// | Object |
- /// D ------ C
- /// </summary>
- public Vector2[,] boundingBoxes2D = new Vector2[(int)Constant.MAX_BATCH_SIZE, 4];
- /// <summary>
- /// a sample of object detection confidence
- /// </summary>
- public float[] confidences = new float[(int)Constant.MAX_BATCH_SIZE];
- /// <summary>
- /// a sample of the object action state
- /// </summary>
- public OBJECT_ACTION_STATE[] actionStates = new OBJECT_ACTION_STATE[(int)Constant.MAX_BATCH_SIZE];
- /// <summary>
- /// a sample of 2d person keypoints.
- /// Not available with DETECTION_MODEL::MULTI_CLASS_BOX.
- /// in some cases, eg. body partially out of the image or missing depth data, some keypoint can not be detected, they will have non finite values.
- /// </summary>
- public Vector2[,] keypoints2D = new Vector2[(int)Constant.MAX_BATCH_SIZE, 18];
- /// <summary>
- /// a sample of 3d person keypoints
- /// Not available with DETECTION_MODEL::MULTI_CLASS_BOX.
- /// in some cases, eg. body partially out of the image or missing depth data, some keypoint can not be detected, they will have non finite values.
- /// </summary>
- public Vector3[,] keypoints = new Vector3[(int)Constant.MAX_BATCH_SIZE, 18];
- /// <summary>
- /// bounds the head with four 2D points.
- /// Expressed in pixels on the original image resolution.
- /// Not available with DETECTION_MODEL.MULTI_CLASS_BOX.
- /// </summary>
- public Vector2[,] headBoundingBoxes2D = new Vector2[(int)Constant.MAX_BATCH_SIZE, 8];
- /// <summary>
- /// bounds the head with eight 3D points.
- /// Defined in sl.InitParameters.UNIT, expressed in RuntimeParameters.measure3DReferenceFrame.
- /// Not available with DETECTION_MODEL.MULTI_CLASS_BOX.
- /// </summary>
- public Vector3[,] headBoundingBoxes = new Vector3[(int)Constant.MAX_BATCH_SIZE, 8];
- /// <summary>
- /// 3D head centroid.
- /// Defined in sl.InitParameters.UNIT, expressed in RuntimeParameters.measure3DReferenceFrame.
- /// Not available with DETECTION_MODEL.MULTI_CLASS_BOX.
- /// </summary>
- public Vector3[] headPositions = new Vector3[(int)Constant.MAX_BATCH_SIZE];
- /// <summary>
- /// Per keypoint detection confidence, can not be lower than the ObjectDetectionRuntimeParameters.detectionConfidenceThreshold.
- /// Not available with DETECTION_MODEL.MULTI_CLASS_BOX.
- /// in some cases, eg. body partially out of the image or missing depth data, some keypoint can not be detected, they will have non finite values.
- /// </summary>
- public float[,] keypointConfidences = new float[(int)Constant.MAX_BATCH_SIZE, 18];
- }
- }// end namespace sl
|