Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
CameraItof Class Reference

#include <camera_itof.h>

Inheritance diagram for CameraItof:
Inheritance graph
[legend]

Public Member Functions

aditof::Status adsd3500DisableCCBM (bool disable) override
 Enable/disable ccb as master. More...
 
aditof::Status adsd3500GetABinvalidationThreshold (int &threshold) override
 Get the AB invalidation threshold. More...
 
aditof::Status adsd3500GetConfidenceThreshold (int &threshold) override
 Get the confidence threshold. More...
 
aditof::Status adsd3500GetEnableMetadatainAB (uint16_t &value) override
 Get state of Enable Metadata in the AB frame. More...
 
aditof::Status adsd3500GetFirmwareVersion (std::string &fwVersion, std::string &fwHash) override
 
aditof::Status adsd3500GetFrameRate (uint16_t &fps) override
 Get Frame Rate. More...
 
aditof::Status adsd3500GetGenericTemplate (uint16_t reg, uint16_t &value) override
 Generic ADSD3500 function for commands not defined in the SDK (yet) More...
 
aditof::Status adsd3500GetImagerErrorCode (uint16_t &errcode) override
 Get error code from the imager. More...
 
aditof::Status adsd3500GetJBLFExponentialTerm (uint16_t &value) override
 Get JBLF Exponential Term. More...
 
aditof::Status adsd3500GetJBLFfilterEnableState (bool &enabled) override
 Get the JBLF enabled state. More...
 
aditof::Status adsd3500GetJBLFfilterSize (int &size) override
 Get the JBLF filter size. More...
 
aditof::Status adsd3500GetJBLFGaussianSigma (uint16_t &value) override
 Get JBLF Gaussian Sigma. More...
 
aditof::Status adsd3500GetLaserTemperature (uint16_t &tmpValue) override
 Get the laser temperature. More...
 
aditof::Status adsd3500GetMIPIOutputSpeed (uint16_t &speed) override
 Get ADSD3500 MIPI output speed. More...
 
aditof::Status adsd3500GetRadialThresholdMax (int &threshold) override
 Get the radial threshold max. More...
 
aditof::Status adsd3500GetRadialThresholdMin (int &threshold) override
 Get the radial threshold min. More...
 
aditof::Status adsd3500GetSensorTemperature (uint16_t &tmpValue) override
 Get the sensor temperature. More...
 
aditof::Status adsd3500GetStatus (int &chipStatus, int &imagerStatus) override
 Returns the chip status. More...
 
aditof::Status adsd3500GetTemperatureCompensationStatus (uint16_t &value) override
 Get Temperature Compensation Status. More...
 
aditof::Status adsd3500GetVCSELDelay (uint16_t &delay) override
 Get the delay for VCSEL - ADSD3100 imager only. More...
 
aditof::Status adsd3500IsCCBMsupported (bool &supported) override
 Check whether CCB as master is supported or not. More...
 
aditof::Status adsd3500ResetIniParamsForMode (const uint16_t mode) override
 Reset the ini parameters from the chip and sets the ones stored in CCB. More...
 
aditof::Status adsd3500SetABinvalidationThreshold (int threshold) override
 Set the AB invalidation threshold. More...
 
aditof::Status adsd3500SetConfidenceThreshold (int threshold) override
 Set the confidence threshold. More...
 
aditof::Status adsd3500setEnableDynamicModeSwitching (bool en) override
 Allows enabling or disabling the Dynamic Mode Switching. NOTE: This must be enabled before configuring the sequence! More...
 
aditof::Status adsd3500SetEnableEdgeConfidence (uint16_t value) override
 Set Enable Edge Confidence. More...
 
aditof::Status adsd3500SetEnableMetadatainAB (uint16_t value) override
 Set Enable Metadata in the AB frame. More...
 
aditof::Status adsd3500SetEnablePhaseInvalidation (uint16_t value) override
 Set Enable Phase Invalidation. More...
 
aditof::Status adsd3500SetEnableTemperatureCompensation (uint16_t value) override
 Set Enable Temperature Compensation. More...
 
aditof::Status adsd3500SetFrameRate (uint16_t fps) override
 Set Frame Rate. More...
 
aditof::Status adsd3500SetGenericTemplate (uint16_t reg, uint16_t value) override
 Generic ADSD3500 function for commands not defined in the SDK (yet) More...
 
aditof::Status adsd3500SetJBLFABThreshold (uint16_t threshold) override
 Get JBLF Max Edge Threshold. More...
 
aditof::Status adsd3500SetJBLFExponentialTerm (uint16_t value) override
 Set JBLF Exponential Term. More...
 
aditof::Status adsd3500SetJBLFfilterEnableState (bool enable) override
 Enable/disable the JBLF filter. More...
 
aditof::Status adsd3500SetJBLFfilterSize (int size) override
 Set the JBLF filter size. More...
 
aditof::Status adsd3500SetJBLFGaussianSigma (uint16_t value) override
 Set JBLF Gaussian Sigma. More...
 
aditof::Status adsd3500SetJBLFMaxEdgeThreshold (uint16_t threshold) override
 Set JBLF Max Edge Threshold. More...
 
aditof::Status adsd3500SetMIPIOutputSpeed (uint16_t speed) override
 Set ADSD3500 MIPI output speed. More...
 
aditof::Status adsd3500SetRadialThresholdMax (int threshold) override
 Set the radial threshold max. More...
 
aditof::Status adsd3500SetRadialThresholdMin (int threshold) override
 Set the radial threshold min. More...
 
aditof::Status adsd3500SetToggleMode (int mode) override
 Enables or disables FSYNC toggle for ADSD3500. More...
 
aditof::Status adsd3500SetVCSELDelay (uint16_t delay) override
 Set the delay for VCSEL - ADSD3100 imager only. More...
 
aditof::Status adsd3500ToggleFsync () override
 Toggles ADSD3500 FSYNC once if automated FSYNC is disabled. More...
 
aditof::Status adsd3500UpdateFirmware (const std::string &filePath) override
 Update the firmware of ADSD3500 with the content found in the specified file. More...
 
aditof::Status adsds3500setDynamicModeSwitchingSequence (const std::vector< std::pair< uint8_t, uint8_t >> &sequence) override
 Configures the sequence to be captured. More...
 
 CameraItof (std::shared_ptr< aditof::DepthSensorInterface > depthSensor, const std::string &ubootVersion, const std::string &kernelVersion, const std::string &sdCardImageVersion, const std::string &netLinkTest)
 
void dropFirstFrame (bool dropFrame) override
 Allow drop first frame. More...
 
aditof::Status enableDepthCompute (bool enable) override
 Enable or disable the depth processing on the frames received from the sensor Must be called after getFrame() where the depth processing happens. More...
 
aditof::Status enableXYZframe (bool enable) override
 Enable the generation of a XYZ frame. The XYZ frame can be enabled or disabled through .ini configuration file but if this method is explicitly called then it will override the option in the .ini file. By default XYZ frame is disabled. More...
 
aditof::Status getAvailableControls (std::vector< std::string > &controls) const override
 Gets the camera's list of controls. More...
 
aditof::Status getAvailableModes (std::vector< uint8_t > &availableModes) const override
 Returns all the modes that are supported by the camera. More...
 
aditof::Status getControl (const std::string &control, std::string &value) const override
 Gets the value of a specific camera control. More...
 
aditof::Status getDetails (aditof::CameraDetails &details) const override
 Gets the current details of the camera. More...
 
aditof::Status getFrameProcessParams (std::map< std::string, std::string > &params) override
 Get the Depth Compute Library ini parameters. More...
 
aditof::Status getImagerType (aditof::ImagerType &imagerType) const override
 Provides the type of the imager. More...
 
std::shared_ptr< aditof::DepthSensorInterfacegetSensor () override
 Gets the sensor of the camera. This gives direct access to low level configuration of the camera sensor. More...
 
aditof::Status initialize (const std::string &configFilepath={}) override
 Initialize the camera. This is required before performing any operation on the camera. More...
 
aditof::Status loadDepthParamsFromJsonFile (const std::string &pathFile, const int16_t mode_in_use=-1) override
 Load adsd parameters from json file. Need setMode to apply. More...
 
void normalizeABBuffer (uint16_t *abBuffer, uint16_t abWidth, uint16_t abHeight, bool advanceScaling, bool useLogScaling) override
 Scale AB image with logarithmic base 10. More...
 
aditof::Status normalizeABFrame (aditof::Frame *frame, bool advanceScaling, bool useLogScaling) override
 Scale AB image with logarithmic base 10 in a Frame instance. More...
 
aditof::Status readSerialNumber (std::string &serialNumber, bool useCacheValue=false) override
 Read serial number from camera and update cache. More...
 
aditof::Status requestFrame (aditof::Frame *frame) override
 Captures data from the camera and assigns it to the given frame. More...
 
aditof::Status saveDepthParamsToJsonFile (const std::string &savePathFile) override
 Save ini file to json format. More...
 
aditof::Status saveModuleCCB (const std::string &filepath) override
 Save the CCB content which is obtained from module memory to a given file path. More...
 
aditof::Status saveModuleCFG (const std::string &filepath) const override
 Save the CFG content which is obtained from module memory to a given file path. More...
 
aditof::Status setControl (const std::string &control, const std::string &value) override
 Sets a specific camera control. More...
 
aditof::Status setFrameProcessParams (std::map< std::string, std::string > &params) override
 Set the Depth Compute Library ini parameters. More...
 
aditof::Status setMode (const uint8_t &mode) override
 Puts the camera into the given mode. More...
 
aditof::Status setSensorConfiguration (const std::string &sensorConf) override
 Set sensor configutation table. More...
 
aditof::Status start () override
 Start the camera. This starts the streaming of data from the camera. More...
 
aditof::Status stop () override
 Stop the camera. This makes the camera to stop streaming. More...
 
 ~CameraItof ()
 
- Public Member Functions inherited from aditof::Camera
virtual ~Camera ()=default
 Destructor. More...
 

Private Types

using noArgCallable = std::function< aditof::Status()>
 

Private Member Functions

void cleanupXYZtables ()
 Delete allocated tables for X, Y, Z. More...
 
void configureSensorModeDetails ()
 
void freeConfigData (void)
 Frees the calibration member variables created while loading the CCB contents. More...
 
bool isConvertibleToDouble (const std::string &str)
 Check if string can convert to double. More...
 
aditof::Status loadConfigData (void)
 Opens the CCB file passed in as part of Json file using initialize(), and loads the calibration blocks into member variable. More...
 
aditof::Status readAdsd3500CCB (std::string &ccb)
 Read the CCB from adsd3500 memory and store in output variable ccb. More...
 
aditof::Status retrieveDepthProcessParams ()
 
aditof::Status setAdsd3500IniParams (const std::map< std::string, std::string > &iniKeyValPairs)
 

Private Attributes

uint8_t m_abBitsPerPixel
 
bool m_abEnabled
 
bool m_adsd3500_master
 
bool m_adsd3500Enabled
 
std::pair< std::string, std::stringm_adsd3500FwGitHash
 
int m_adsd3500FwVersionInt
 
aditof::Adsd3500Status m_adsd3500Status
 
aditof::ADSDErrors m_adsdErrors
 
std::vector< uint8_t > m_availableModes
 
std::vector< aditof::DepthSensorModeDetailsm_availableSensorModeDetails
 
FileData m_calData = {NULL, 0}
 
int16_t m_cameraFps
 
std::string m_ccb_calibrationFile
 
uint8_t m_confBitsPerPixel
 
std::vector< std::pair< uint8_t, uint8_t > > m_configDmsSequence
 
std::unordered_map< std::string, std::stringm_controls
 
std::map< int, std::map< std::string, std::string > > m_depth_params_map
 
uint8_t m_depthBitsPerPixel
 
FileData m_depthINIData
 
std::map< std::string, FileDatam_depthINIDataMap
 
std::shared_ptr< aditof::DepthSensorInterfacem_depthSensor
 
aditof::CameraDetails m_details
 
bool m_devStarted
 
bool m_devStreaming
 
bool m_dropFirstFrame
 
bool m_dropFrameOnce
 
bool m_enableDepthCompute
 
int16_t m_enableEdgeConfidence
 
int16_t m_enableMetaDatainAB
 
int16_t m_enableTempCompenstation
 
int16_t m_fsyncMode
 
bool m_fwUpdated
 
aditof::ImagerType m_imagerType
 
std::string m_ini_depth
 
std::map< std::string, std::stringm_ini_depth_map
 
std::map< std::string, std::stringm_iniKeyValPairs
 
std::string m_initConfigFilePath
 
bool m_isOffline
 
bool m_loadedConfigData
 
int16_t m_mipiOutputSpeed
 
aditof::DepthSensorModeDetails m_modeDetailsCache
 
int m_modesVersion
 
std::string m_netLinkTest
 
std::map< std::string, noArgCallablem_noArgCallables
 
bool m_pcmFrame
 
std::vector< std::pair< std::string, int32_t > > m_sensor_settings
 
std::string m_sensorFirmwareFile
 
bool m_tempSensorInitialized
 
TofiXYZDealiasData m_xyz_dealias_data [MAX_N_MODES+1]
 
bool m_xyzEnabled
 
bool m_xyzSetViaApi
 
XYZTable m_xyzTable
 

Detailed Description

Definition at line 46 of file camera_itof.h.

Member Typedef Documentation

◆ noArgCallable

using CameraItof::noArgCallable = std::function<aditof::Status()>
private

Definition at line 205 of file camera_itof.h.

Constructor & Destructor Documentation

◆ CameraItof()

CameraItof::CameraItof ( std::shared_ptr< aditof::DepthSensorInterface depthSensor,
const std::string ubootVersion,
const std::string kernelVersion,
const std::string sdCardImageVersion,
const std::string netLinkTest 
)

Definition at line 67 of file camera_itof.cpp.

◆ ~CameraItof()

CameraItof::~CameraItof ( )

Definition at line 115 of file camera_itof.cpp.

Member Function Documentation

◆ adsd3500DisableCCBM()

aditof::Status CameraItof::adsd3500DisableCCBM ( bool  disable)
overridevirtual

Enable/disable ccb as master.

Parameters
[in]disable- set to: 1 - disable, 0 - enable
Returns
Status

Implements aditof::Camera.

Definition at line 1856 of file camera_itof.cpp.

◆ adsd3500GetABinvalidationThreshold()

aditof::Status CameraItof::adsd3500GetABinvalidationThreshold ( int &  threshold)
overridevirtual

Get the AB invalidation threshold.

Parameters
[out]threshold
Returns
Status

Implements aditof::Camera.

Definition at line 1691 of file camera_itof.cpp.

◆ adsd3500GetConfidenceThreshold()

aditof::Status CameraItof::adsd3500GetConfidenceThreshold ( int &  threshold)
overridevirtual

Get the confidence threshold.

Parameters
[out]threshold
Returns
Status

Implements aditof::Camera.

Definition at line 1700 of file camera_itof.cpp.

◆ adsd3500GetEnableMetadatainAB()

aditof::Status CameraItof::adsd3500GetEnableMetadatainAB ( uint16_t &  value)
overridevirtual

Get state of Enable Metadata in the AB frame.

Parameters
[out]value- See "Get Output Metadata in AB Frame status" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1840 of file camera_itof.cpp.

◆ adsd3500GetFirmwareVersion()

aditof::Status CameraItof::adsd3500GetFirmwareVersion ( std::string fwVersion,
std::string fwHash 
)
overridevirtual

Get the ASDSD3500 firmware version from the ADSD3500

Parameters
[out]fwVersion- the ADSD3500 firmware version
[out]fwHash- the ADSD3500 firmware git commit hash

Implements aditof::Camera.

Definition at line 1654 of file camera_itof.cpp.

◆ adsd3500GetFrameRate()

aditof::Status CameraItof::adsd3500GetFrameRate ( uint16_t &  fps)
overridevirtual

Get Frame Rate.

Parameters
[out]fps- See "Get Frame Rate" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1795 of file camera_itof.cpp.

◆ adsd3500GetGenericTemplate()

aditof::Status CameraItof::adsd3500GetGenericTemplate ( uint16_t  reg,
uint16_t &  value 
)
overridevirtual

Generic ADSD3500 function for commands not defined in the SDK (yet)

Parameters
[in]reg- 16-bit ADSD3500 register
[out]value- 16-bit value read from the register
Returns
Status

Implements aditof::Camera.

Definition at line 1850 of file camera_itof.cpp.

◆ adsd3500GetImagerErrorCode()

aditof::Status CameraItof::adsd3500GetImagerErrorCode ( uint16_t &  errcode)
overridevirtual

Get error code from the imager.

Parameters
[out]errcode- See "Get Imager Error Code" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1754 of file camera_itof.cpp.

◆ adsd3500GetJBLFExponentialTerm()

aditof::Status CameraItof::adsd3500GetJBLFExponentialTerm ( uint16_t &  value)
overridevirtual

Get JBLF Exponential Term.

Parameters
[out]value- See "Get JBLF Exponential Term" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1790 of file camera_itof.cpp.

◆ adsd3500GetJBLFfilterEnableState()

aditof::Status CameraItof::adsd3500GetJBLFfilterEnableState ( bool &  enabled)
overridevirtual

Get the JBLF enabled state.

Parameters
[out]enabled
Returns
Status

Implements aditof::Camera.

Definition at line 1709 of file camera_itof.cpp.

◆ adsd3500GetJBLFfilterSize()

aditof::Status CameraItof::adsd3500GetJBLFfilterSize ( int &  size)
overridevirtual

Get the JBLF filter size.

Parameters
[out]size
Returns
Status

Implements aditof::Camera.

Definition at line 1720 of file camera_itof.cpp.

◆ adsd3500GetJBLFGaussianSigma()

aditof::Status CameraItof::adsd3500GetJBLFGaussianSigma ( uint16_t &  value)
overridevirtual

Get JBLF Gaussian Sigma.

Parameters
[out]value- See "Get JBLF Gaussian Sigma" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1780 of file camera_itof.cpp.

◆ adsd3500GetLaserTemperature()

aditof::Status CameraItof::adsd3500GetLaserTemperature ( uint16_t &  tmpValue)
overridevirtual

Get the laser temperature.

Parameters
[out]tmpValue- Values in Celsius degree
Returns
Status

Implements aditof::Camera.

Definition at line 1933 of file camera_itof.cpp.

◆ adsd3500GetMIPIOutputSpeed()

aditof::Status CameraItof::adsd3500GetMIPIOutputSpeed ( uint16_t &  speed)
overridevirtual

Get ADSD3500 MIPI output speed.

Parameters
[out]speed- See "Get MIPI Output Speed" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1749 of file camera_itof.cpp.

◆ adsd3500GetRadialThresholdMax()

aditof::Status CameraItof::adsd3500GetRadialThresholdMax ( int &  threshold)
overridevirtual

Get the radial threshold max.

Parameters
[out]threshold
Returns
Status

Implements aditof::Camera.

Definition at line 1739 of file camera_itof.cpp.

◆ adsd3500GetRadialThresholdMin()

aditof::Status CameraItof::adsd3500GetRadialThresholdMin ( int &  threshold)
overridevirtual

Get the radial threshold min.

Parameters
[out]threshold
Returns
Status

Implements aditof::Camera.

Definition at line 1729 of file camera_itof.cpp.

◆ adsd3500GetSensorTemperature()

aditof::Status CameraItof::adsd3500GetSensorTemperature ( uint16_t &  tmpValue)
overridevirtual

Get the sensor temperature.

Parameters
[out]tmpValue- Values in Celsius degree
Returns
Status

Implements aditof::Camera.

Definition at line 1916 of file camera_itof.cpp.

◆ adsd3500GetStatus()

aditof::Status CameraItof::adsd3500GetStatus ( int &  chipStatus,
int &  imagerStatus 
)
overridevirtual

Returns the chip status.

Parameters
[out]chipStatus- chip status (error) value
[out]imagerStatus- imager status (error) value
Returns
Status

Implements aditof::Camera.

Definition at line 1880 of file camera_itof.cpp.

◆ adsd3500GetTemperatureCompensationStatus()

aditof::Status CameraItof::adsd3500GetTemperatureCompensationStatus ( uint16_t &  value)
overridevirtual

Get Temperature Compensation Status.

Parameters
[out]value- See "Get Temperature Compensation Status" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1822 of file camera_itof.cpp.

◆ adsd3500GetVCSELDelay()

aditof::Status CameraItof::adsd3500GetVCSELDelay ( uint16_t &  delay)
overridevirtual

Get the delay for VCSEL - ADSD3100 imager only.

Parameters
[out]delay- See "Get VCSEL Delay" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1763 of file camera_itof.cpp.

◆ adsd3500IsCCBMsupported()

aditof::Status CameraItof::adsd3500IsCCBMsupported ( bool &  supported)
overridevirtual

Check whether CCB as master is supported or not.

Parameters
[out]supported- Will be set to true in case CCBM is supported
Returns
Status

Implements aditof::Camera.

Definition at line 1860 of file camera_itof.cpp.

◆ adsd3500ResetIniParamsForMode()

aditof::Status CameraItof::adsd3500ResetIniParamsForMode ( const uint16_t  mode)
overridevirtual

Reset the ini parameters from the chip and sets the ones stored in CCB.

Parameters
mode- Camera mode to be reset
Returns
Status

Implements aditof::Camera.

Definition at line 564 of file camera_itof.cpp.

◆ adsd3500SetABinvalidationThreshold()

aditof::Status CameraItof::adsd3500SetABinvalidationThreshold ( int  threshold)
overridevirtual

Set the AB invalidation threshold.

Parameters
[in]threshold
Returns
Status

Implements aditof::Camera.

Definition at line 1687 of file camera_itof.cpp.

◆ adsd3500SetConfidenceThreshold()

aditof::Status CameraItof::adsd3500SetConfidenceThreshold ( int  threshold)
overridevirtual

Set the confidence threshold.

Parameters
[in]threshold
Returns
Status

Implements aditof::Camera.

Definition at line 1697 of file camera_itof.cpp.

◆ adsd3500setEnableDynamicModeSwitching()

aditof::Status CameraItof::adsd3500setEnableDynamicModeSwitching ( bool  enable)
overridevirtual

Allows enabling or disabling the Dynamic Mode Switching. NOTE: This must be enabled before configuring the sequence!

Parameters
[in]enable- Set to true to enable and false to disable
Returns
Status

Implements aditof::Camera.

Definition at line 2112 of file camera_itof.cpp.

◆ adsd3500SetEnableEdgeConfidence()

aditof::Status CameraItof::adsd3500SetEnableEdgeConfidence ( uint16_t  value)
overridevirtual

Set Enable Edge Confidence.

Parameters
[in]value- See "Set Enable Edge Confidence" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1817 of file camera_itof.cpp.

◆ adsd3500SetEnableMetadatainAB()

aditof::Status CameraItof::adsd3500SetEnableMetadatainAB ( uint16_t  value)
overridevirtual

Set Enable Metadata in the AB frame.

Parameters
[in]value- See "Enable/Disable Output Metadata in AB Frame" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1836 of file camera_itof.cpp.

◆ adsd3500SetEnablePhaseInvalidation()

aditof::Status CameraItof::adsd3500SetEnablePhaseInvalidation ( uint16_t  value)
overridevirtual

Set Enable Phase Invalidation.

Parameters
[out]value- See "Set Enable Phase Invalidation" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1827 of file camera_itof.cpp.

◆ adsd3500SetEnableTemperatureCompensation()

aditof::Status CameraItof::adsd3500SetEnableTemperatureCompensation ( uint16_t  value)
overridevirtual

Set Enable Temperature Compensation.

Parameters
[out]value- See "Set Enable Temperature Compensation" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1832 of file camera_itof.cpp.

◆ adsd3500SetFrameRate()

aditof::Status CameraItof::adsd3500SetFrameRate ( uint16_t  fps)
overridevirtual

Set Frame Rate.

Parameters
[out]fps- See "Set Frame Rate" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1800 of file camera_itof.cpp.

◆ adsd3500SetGenericTemplate()

aditof::Status CameraItof::adsd3500SetGenericTemplate ( uint16_t  reg,
uint16_t  value 
)
overridevirtual

Generic ADSD3500 function for commands not defined in the SDK (yet)

Parameters
[in]reg- 16-bit ADSD3500 register
[in]value- 16-bit value to write to the register
Returns
Status

Implements aditof::Camera.

Definition at line 1845 of file camera_itof.cpp.

◆ adsd3500SetJBLFABThreshold()

aditof::Status CameraItof::adsd3500SetJBLFABThreshold ( uint16_t  threshold)
overridevirtual

Get JBLF Max Edge Threshold.

Parameters
[out]threshold- See "Get JBLF Max Edge Threshold" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1772 of file camera_itof.cpp.

◆ adsd3500SetJBLFExponentialTerm()

aditof::Status CameraItof::adsd3500SetJBLFExponentialTerm ( uint16_t  value)
overridevirtual

Set JBLF Exponential Term.

Parameters
[in]value- See "Set JBLF Exponential Term" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1786 of file camera_itof.cpp.

◆ adsd3500SetJBLFfilterEnableState()

aditof::Status CameraItof::adsd3500SetJBLFfilterEnableState ( bool  enable)
overridevirtual

Enable/disable the JBLF filter.

Parameters
[in]enable
Returns
Status

Implements aditof::Camera.

Definition at line 1706 of file camera_itof.cpp.

◆ adsd3500SetJBLFfilterSize()

aditof::Status CameraItof::adsd3500SetJBLFfilterSize ( int  size)
overridevirtual

Set the JBLF filter size.

Parameters
[in]size- Supported sizes are: 3, 5, 7
Returns
Status

Implements aditof::Camera.

Definition at line 1717 of file camera_itof.cpp.

◆ adsd3500SetJBLFGaussianSigma()

aditof::Status CameraItof::adsd3500SetJBLFGaussianSigma ( uint16_t  value)
overridevirtual

Set JBLF Gaussian Sigma.

Parameters
[in]value- See "Set JBLF Gaussian Sigma" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1776 of file camera_itof.cpp.

◆ adsd3500SetJBLFMaxEdgeThreshold()

aditof::Status CameraItof::adsd3500SetJBLFMaxEdgeThreshold ( uint16_t  threshold)
overridevirtual

Set JBLF Max Edge Threshold.

Parameters
[in]threshold- See "Set JBLF Max Edge Threshold" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1768 of file camera_itof.cpp.

◆ adsd3500SetMIPIOutputSpeed()

aditof::Status CameraItof::adsd3500SetMIPIOutputSpeed ( uint16_t  speed)
overridevirtual

Set ADSD3500 MIPI output speed.

Parameters
[in]speed- See "Set MIPI Output Speed" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1745 of file camera_itof.cpp.

◆ adsd3500SetRadialThresholdMax()

aditof::Status CameraItof::adsd3500SetRadialThresholdMax ( int  threshold)
overridevirtual

Set the radial threshold max.

Parameters
[in]threshold
Returns
Status

Implements aditof::Camera.

Definition at line 1735 of file camera_itof.cpp.

◆ adsd3500SetRadialThresholdMin()

aditof::Status CameraItof::adsd3500SetRadialThresholdMin ( int  threshold)
overridevirtual

Set the radial threshold min.

Parameters
[in]threshold
Returns
Status

Implements aditof::Camera.

Definition at line 1726 of file camera_itof.cpp.

◆ adsd3500SetToggleMode()

aditof::Status CameraItof::adsd3500SetToggleMode ( int  mode)
overridevirtual

Enables or disables FSYNC toggle for ADSD3500.

Parameters
[in]mode- 2 = Fsync pin set as HiZ ; 1 = Toggle at user specified framerate ; 0 = Toggle controlled via adsd3500ToggleFsync ;
Returns
Status

Implements aditof::Camera.

Definition at line 1616 of file camera_itof.cpp.

◆ adsd3500SetVCSELDelay()

aditof::Status CameraItof::adsd3500SetVCSELDelay ( uint16_t  delay)
overridevirtual

Set the delay for VCSEL - ADSD3100 imager only.

Parameters
[in]delay- See "Set VCSEL Delay" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500
Returns
Status

Implements aditof::Camera.

Definition at line 1759 of file camera_itof.cpp.

◆ adsd3500ToggleFsync()

aditof::Status CameraItof::adsd3500ToggleFsync ( )
overridevirtual

Toggles ADSD3500 FSYNC once if automated FSYNC is disabled.

Returns
Status

Implements aditof::Camera.

Definition at line 1636 of file camera_itof.cpp.

◆ adsd3500UpdateFirmware()

aditof::Status CameraItof::adsd3500UpdateFirmware ( const std::string fwFilePath)
overridevirtual

Update the firmware of ADSD3500 with the content found in the specified file.

Parameters
[in]fwFilePath- A path to a file (including file name and extension) where the firmware for adsd3500 is stored.
Returns
Status

Implements aditof::Camera.

Definition at line 1003 of file camera_itof.cpp.

◆ adsds3500setDynamicModeSwitchingSequence()

aditof::Status CameraItof::adsds3500setDynamicModeSwitchingSequence ( const std::vector< std::pair< uint8_t, uint8_t >> &  sequence)
overridevirtual

Configures the sequence to be captured.

Parameters
[in]sequence- accepts a list of maximum 8 pairs. The first item of the pair refers to the mode to be captured and the second item refers to how many times the mode should be repeated before moving on to the next pair. The entire sequence will repeat over and over again until streaming is stopped. The first item must be a valid mode. The modes being sequenced must have the exact same resolution. The second item must be between 0 and 15. If 0 is set, the mode will be skipped (will repeat 0 times). Usage example 1: calling this: adsds3500setDynamicModeSwitchingSequence( { {6, 1}, {5, 2}, {2, 3}, {3, 4}, {2, 5} } ); will create sequence: 655222333322222655222...

Usage example 2: calling this: adsds3500setDynamicModeSwitchingSequence( { {6, 15}, {6, 15}, {6, 15}, {6, 15}, {6, 15}, {5, 1} } ); will create sequence: 6666(75 times)5666...

NOTE: Only ADSD3030 supports setting how many times the mode should be repeated!

Returns
Status

Implements aditof::Camera.

Definition at line 2117 of file camera_itof.cpp.

◆ cleanupXYZtables()

void CameraItof::cleanupXYZtables ( )
private

Delete allocated tables for X, Y, Z.

Definition at line 2091 of file camera_itof.cpp.

◆ configureSensorModeDetails()

void CameraItof::configureSensorModeDetails ( )
private

Configure the sensor with various settings that affect the frame type.

Definition at line 1231 of file camera_itof.cpp.

◆ dropFirstFrame()

void CameraItof::dropFirstFrame ( bool  dropFrame)
overridevirtual

Allow drop first frame.

Parameters
dropFrame- Drop the first frame if true
Returns
void

Implements aditof::Camera.

Definition at line 1607 of file camera_itof.cpp.

◆ enableDepthCompute()

aditof::Status CameraItof::enableDepthCompute ( bool  enable)
overridevirtual

Enable or disable the depth processing on the frames received from the sensor Must be called after getFrame() where the depth processing happens.

Parameters
[in]enable- set to true to enable depth processing. Set to false otherwise.
Returns
Status

Implements aditof::Camera.

Definition at line 984 of file camera_itof.cpp.

◆ enableXYZframe()

aditof::Status CameraItof::enableXYZframe ( bool  enable)
overridevirtual

Enable the generation of a XYZ frame. The XYZ frame can be enabled or disabled through .ini configuration file but if this method is explicitly called then it will override the option in the .ini file. By default XYZ frame is disabled.

Parameters
[in]enable- set to true to enable the generation of XYZ, set to false otherwise.
Returns
Status

Implements aditof::Camera.

Definition at line 977 of file camera_itof.cpp.

◆ freeConfigData()

void CameraItof::freeConfigData ( void  )
private

Frees the calibration member variables created while loading the CCB contents.

Returns
None

Definition at line 889 of file camera_itof.cpp.

◆ getAvailableControls()

aditof::Status CameraItof::getAvailableControls ( std::vector< std::string > &  controls) const
overridevirtual

Gets the camera's list of controls.

Parameters
[out]controls
Returns
Status

Implements aditof::Camera.

Definition at line 808 of file camera_itof.cpp.

◆ getAvailableModes()

aditof::Status CameraItof::getAvailableModes ( std::vector< uint8_t > &  availableModes) const
overridevirtual

Returns all the modes that are supported by the camera.

Parameters
[out]availableModes
Returns
Status

Implements aditof::Camera.

Definition at line 569 of file camera_itof.cpp.

◆ getControl()

aditof::Status CameraItof::getControl ( const std::string control,
std::string value 
) const
overridevirtual

Gets the value of a specific camera control.

Parameters
[in]control- Control name
[out]value- Control value
Returns
Status

Implements aditof::Camera.

Definition at line 840 of file camera_itof.cpp.

◆ getDetails()

aditof::Status CameraItof::getDetails ( aditof::CameraDetails details) const
overridevirtual

Gets the current details of the camera.

Parameters
[out]details
Returns
Status

Implements aditof::Camera.

Definition at line 794 of file camera_itof.cpp.

◆ getFrameProcessParams()

aditof::Status CameraItof::getFrameProcessParams ( std::map< std::string, std::string > &  params)
overridevirtual

Get the Depth Compute Library ini parameters.

Parameters
params- a dictionary of parameters
Returns
Status

Implements aditof::Camera.

Definition at line 538 of file camera_itof.cpp.

◆ getImagerType()

aditof::Status CameraItof::getImagerType ( aditof::ImagerType imagerType) const
overridevirtual

Provides the type of the imager.

Parameters
[out]imagerType- Will be set with the imager type
Returns
Status

Implements aditof::Camera.

Definition at line 2106 of file camera_itof.cpp.

◆ getSensor()

std::shared_ptr< aditof::DepthSensorInterface > CameraItof::getSensor ( )
overridevirtual

Gets the sensor of the camera. This gives direct access to low level configuration of the camera sensor.

Returns
std::shared_ptr<DepthSensorInterface>

Implements aditof::Camera.

Definition at line 803 of file camera_itof.cpp.

◆ initialize()

aditof::Status CameraItof::initialize ( const std::string configFilepath = {})
overridevirtual

Initialize the camera. This is required before performing any operation on the camera.

Parameters
configFilepath- The JSON configuration files which should be specific to the given module. The expected value is a file name (including extension) or left empty.
Returns
Status

Implements aditof::Camera.

Definition at line 121 of file camera_itof.cpp.

◆ isConvertibleToDouble()

bool CameraItof::isConvertibleToDouble ( const std::string str)
private

Check if string can convert to double.

Definition at line 1597 of file camera_itof.cpp.

◆ loadConfigData()

aditof::Status CameraItof::loadConfigData ( void  )
private

Opens the CCB file passed in as part of Json file using initialize(), and loads the calibration blocks into member variable.

Returns
aditof::Status
See also
aditof::Status
config_default.json

Definition at line 855 of file camera_itof.cpp.

◆ loadDepthParamsFromJsonFile()

aditof::Status CameraItof::loadDepthParamsFromJsonFile ( const std::string pathFileloadDepthParamsFromJsonFile,
const int16_t  mode_in_use = -1 
)
overridevirtual

Load adsd parameters from json file. Need setMode to apply.

Parameters
pathFileloadDepthParamsFromJsonFile- Path to load from json file
mode_in_use- Specify to read details for a specifc mode
Returns
Status

Implements aditof::Camera.

Definition at line 1457 of file camera_itof.cpp.

◆ normalizeABBuffer()

void CameraItof::normalizeABBuffer ( uint16_t *  abBuffer,
uint16_t  abWidth,
uint16_t  abHeight,
bool  advanceScaling,
bool  useLogScaling 
)
overridevirtual

Scale AB image with logarithmic base 10.

Parameters
abBuffer- Pointer to the AB buffer
abWidth- Width (in pixels) of the AB buffer
abHeight- Height (in pixels) of the AB buffer
advanceScaling- If is true then use advance AB scaling.
useLogScaling- If is false is applied the normalization between 0 and 255, if is true is applied normalization between 0 and 255 and log10
Returns
Status

Implements aditof::Camera.

Definition at line 681 of file camera_itof.cpp.

◆ normalizeABFrame()

aditof::Status CameraItof::normalizeABFrame ( aditof::Frame frame,
bool  advanceScaling,
bool  useLogScaling 
)
overridevirtual

Scale AB image with logarithmic base 10 in a Frame instance.

Parameters
frame- The frame of the camera
advanceScaling- If is true then use advance AB scaling.
useLogScaling- If is false is applied the normalization between 0 and 255, if is true is applied normalization between 0 and 255 and log10
Returns
Status

Implements aditof::Camera.

Definition at line 763 of file camera_itof.cpp.

◆ readAdsd3500CCB()

aditof::Status CameraItof::readAdsd3500CCB ( std::string ccb)
private

Read the CCB from adsd3500 memory and store in output variable ccb.

Parameters
[out]ccb- where to store the CCB content
Returns
Status
See also
Status

Definition at line 1144 of file camera_itof.cpp.

◆ readSerialNumber()

aditof::Status CameraItof::readSerialNumber ( std::string serialNumber,
bool  useCacheValue = false 
)
overridevirtual

Read serial number from camera and update cache.

Parameters
[out]serialNumber- Will contain serial number
[in]useCacheValue- If it is false it will read from camera and if it is true it will return serialNumber from cache
Returns
Status

Implements aditof::Camera.

Definition at line 905 of file camera_itof.cpp.

◆ requestFrame()

aditof::Status CameraItof::requestFrame ( aditof::Frame frame)
overridevirtual

Captures data from the camera and assigns it to the given frame.

Parameters
frame- The frame to which the camera data should be assign
Returns
Status

Implements aditof::Camera.

Definition at line 581 of file camera_itof.cpp.

◆ retrieveDepthProcessParams()

aditof::Status CameraItof::retrieveDepthProcessParams ( )
private

Reads the depth process parameters from camera

Definition at line 1345 of file camera_itof.cpp.

◆ saveDepthParamsToJsonFile()

aditof::Status CameraItof::saveDepthParamsToJsonFile ( const std::string savePathFile)
overridevirtual

Save ini file to json format.

Parameters
savePathFile- Path to save json file
Returns
Status

Implements aditof::Camera.

Definition at line 1367 of file camera_itof.cpp.

◆ saveModuleCCB()

aditof::Status CameraItof::saveModuleCCB ( const std::string filepath)
overridevirtual

Save the CCB content which is obtained from module memory to a given file path.

Parameters
[in]filepath- A path to a file (including file name and extension) where the CCB should be stored.
Returns
Status

Implements aditof::Camera.

Definition at line 939 of file camera_itof.cpp.

◆ saveModuleCFG()

aditof::Status CameraItof::saveModuleCFG ( const std::string filepath) const
overridevirtual

Save the CFG content which is obtained from module memory to a given file path.

Parameters
[in]filepath- A path to a file (including file name and extension) where the CFG should be stored.
Returns
Status

Implements aditof::Camera.

Definition at line 967 of file camera_itof.cpp.

◆ setAdsd3500IniParams()

aditof::Status CameraItof::setAdsd3500IniParams ( const std::map< std::string, std::string > &  iniKeyValPairs)
private

Configure ADSD3500 with ini parameters

Parameters
[in]iniKeyValPairs- ini parameteres to use

Definition at line 1951 of file camera_itof.cpp.

◆ setControl()

aditof::Status CameraItof::setControl ( const std::string control,
const std::string value 
)
overridevirtual

Sets a specific camera control.

Parameters
[in]control- Control name
[in]value- Control value
Returns
Status

Implements aditof::Camera.

Definition at line 821 of file camera_itof.cpp.

◆ setFrameProcessParams()

aditof::Status CameraItof::setFrameProcessParams ( std::map< std::string, std::string > &  params)
overridevirtual

Set the Depth Compute Library ini parameters.

Parameters
params- a dictionary of parameters
Returns
Status

Implements aditof::Camera.

Definition at line 548 of file camera_itof.cpp.

◆ setMode()

aditof::Status CameraItof::setMode ( const uint8_t &  mode)
overridevirtual

Puts the camera into the given mode.

Parameters
mode- The mode of the camera
Returns
Status

Implements aditof::Camera.

Definition at line 328 of file camera_itof.cpp.

◆ setSensorConfiguration()

aditof::Status CameraItof::setSensorConfiguration ( const std::string sensorConf)
overridevirtual

Set sensor configutation table.

Parameters
sensorConf- Configuration table name string like e.g. standard, standardraw, custom and customraw
Returns
Status

Implements aditof::Camera.

Definition at line 1612 of file camera_itof.cpp.

◆ start()

aditof::Status CameraItof::start ( )
overridevirtual

Start the camera. This starts the streaming of data from the camera.

Returns
Status

Implements aditof::Camera.

Definition at line 302 of file camera_itof.cpp.

◆ stop()

aditof::Status CameraItof::stop ( )
overridevirtual

Stop the camera. This makes the camera to stop streaming.

Returns
Status

Implements aditof::Camera.

Definition at line 315 of file camera_itof.cpp.

Member Data Documentation

◆ m_abBitsPerPixel

uint8_t CameraItof::m_abBitsPerPixel
private

Definition at line 235 of file camera_itof.h.

◆ m_abEnabled

bool CameraItof::m_abEnabled
private

Definition at line 233 of file camera_itof.h.

◆ m_adsd3500_master

bool CameraItof::m_adsd3500_master
private

Definition at line 217 of file camera_itof.h.

◆ m_adsd3500Enabled

bool CameraItof::m_adsd3500Enabled
private

Definition at line 216 of file camera_itof.h.

◆ m_adsd3500FwGitHash

std::pair<std::string, std::string> CameraItof::m_adsd3500FwGitHash
private

Definition at line 252 of file camera_itof.h.

◆ m_adsd3500FwVersionInt

int CameraItof::m_adsd3500FwVersionInt
private

Definition at line 253 of file camera_itof.h.

◆ m_adsd3500Status

aditof::Adsd3500Status CameraItof::m_adsd3500Status
private

Definition at line 256 of file camera_itof.h.

◆ m_adsdErrors

aditof::ADSDErrors CameraItof::m_adsdErrors
private

Definition at line 211 of file camera_itof.h.

◆ m_availableModes

std::vector<uint8_t> CameraItof::m_availableModes
private

Definition at line 241 of file camera_itof.h.

◆ m_availableSensorModeDetails

std::vector<aditof::DepthSensorModeDetails> CameraItof::m_availableSensorModeDetails
private

Definition at line 240 of file camera_itof.h.

◆ m_calData

FileData CameraItof::m_calData = {NULL, 0}
private

Definition at line 221 of file camera_itof.h.

◆ m_cameraFps

int16_t CameraItof::m_cameraFps
private

Definition at line 244 of file camera_itof.h.

◆ m_ccb_calibrationFile

std::string CameraItof::m_ccb_calibrationFile
private

Definition at line 229 of file camera_itof.h.

◆ m_confBitsPerPixel

uint8_t CameraItof::m_confBitsPerPixel
private

Definition at line 236 of file camera_itof.h.

◆ m_configDmsSequence

std::vector<std::pair<uint8_t, uint8_t> > CameraItof::m_configDmsSequence
private

Definition at line 263 of file camera_itof.h.

◆ m_controls

std::unordered_map<std::string, std::string> CameraItof::m_controls
private

Definition at line 209 of file camera_itof.h.

◆ m_depth_params_map

std::map<int, std::map<std::string, std::string> > CameraItof::m_depth_params_map
private

Definition at line 232 of file camera_itof.h.

◆ m_depthBitsPerPixel

uint8_t CameraItof::m_depthBitsPerPixel
private

Definition at line 234 of file camera_itof.h.

◆ m_depthINIData

FileData CameraItof::m_depthINIData
private

Definition at line 223 of file camera_itof.h.

◆ m_depthINIDataMap

std::map<std::string, FileData> CameraItof::m_depthINIDataMap
private

Definition at line 224 of file camera_itof.h.

◆ m_depthSensor

std::shared_ptr<aditof::DepthSensorInterface> CameraItof::m_depthSensor
private

Definition at line 208 of file camera_itof.h.

◆ m_details

aditof::CameraDetails CameraItof::m_details
private

Definition at line 207 of file camera_itof.h.

◆ m_devStarted

bool CameraItof::m_devStarted
private

Definition at line 213 of file camera_itof.h.

◆ m_devStreaming

bool CameraItof::m_devStreaming
private

Definition at line 214 of file camera_itof.h.

◆ m_dropFirstFrame

bool CameraItof::m_dropFirstFrame
private

Definition at line 261 of file camera_itof.h.

◆ m_dropFrameOnce

bool CameraItof::m_dropFrameOnce
private

Definition at line 262 of file camera_itof.h.

◆ m_enableDepthCompute

bool CameraItof::m_enableDepthCompute
private

Definition at line 258 of file camera_itof.h.

◆ m_enableEdgeConfidence

int16_t CameraItof::m_enableEdgeConfidence
private

Definition at line 249 of file camera_itof.h.

◆ m_enableMetaDatainAB

int16_t CameraItof::m_enableMetaDatainAB
private

Definition at line 248 of file camera_itof.h.

◆ m_enableTempCompenstation

int16_t CameraItof::m_enableTempCompenstation
private

Definition at line 247 of file camera_itof.h.

◆ m_fsyncMode

int16_t CameraItof::m_fsyncMode
private

Definition at line 245 of file camera_itof.h.

◆ m_fwUpdated

bool CameraItof::m_fwUpdated
private

Definition at line 255 of file camera_itof.h.

◆ m_imagerType

aditof::ImagerType CameraItof::m_imagerType
private

Definition at line 260 of file camera_itof.h.

◆ m_ini_depth

std::string CameraItof::m_ini_depth
private

Definition at line 230 of file camera_itof.h.

◆ m_ini_depth_map

std::map<std::string, std::string> CameraItof::m_ini_depth_map
private

Definition at line 231 of file camera_itof.h.

◆ m_iniKeyValPairs

std::map<std::string, std::string> CameraItof::m_iniKeyValPairs
private

Definition at line 250 of file camera_itof.h.

◆ m_initConfigFilePath

std::string CameraItof::m_initConfigFilePath
private

Definition at line 259 of file camera_itof.h.

◆ m_isOffline

bool CameraItof::m_isOffline
private

Definition at line 218 of file camera_itof.h.

◆ m_loadedConfigData

bool CameraItof::m_loadedConfigData
private

Definition at line 226 of file camera_itof.h.

◆ m_mipiOutputSpeed

int16_t CameraItof::m_mipiOutputSpeed
private

Definition at line 246 of file camera_itof.h.

◆ m_modeDetailsCache

aditof::DepthSensorModeDetails CameraItof::m_modeDetailsCache
private

Definition at line 242 of file camera_itof.h.

◆ m_modesVersion

int CameraItof::m_modesVersion
private

Definition at line 254 of file camera_itof.h.

◆ m_netLinkTest

std::string CameraItof::m_netLinkTest
private

Definition at line 219 of file camera_itof.h.

◆ m_noArgCallables

std::map<std::string, noArgCallable> CameraItof::m_noArgCallables
private

Definition at line 210 of file camera_itof.h.

◆ m_pcmFrame

bool CameraItof::m_pcmFrame
private

Definition at line 239 of file camera_itof.h.

◆ m_sensor_settings

std::vector<std::pair<std::string, int32_t> > CameraItof::m_sensor_settings
private

Definition at line 243 of file camera_itof.h.

◆ m_sensorFirmwareFile

std::string CameraItof::m_sensorFirmwareFile
private

Definition at line 228 of file camera_itof.h.

◆ m_tempSensorInitialized

bool CameraItof::m_tempSensorInitialized
private

Definition at line 215 of file camera_itof.h.

◆ m_xyz_dealias_data

TofiXYZDealiasData CameraItof::m_xyz_dealias_data[MAX_N_MODES+1]
private

Definition at line 225 of file camera_itof.h.

◆ m_xyzEnabled

bool CameraItof::m_xyzEnabled
private

Definition at line 237 of file camera_itof.h.

◆ m_xyzSetViaApi

bool CameraItof::m_xyzSetViaApi
private

Definition at line 238 of file camera_itof.h.

◆ m_xyzTable

XYZTable CameraItof::m_xyzTable
private

Definition at line 257 of file camera_itof.h.


The documentation for this class was generated from the following files:


libaditof
Author(s):
autogenerated on Wed May 21 2025 02:07:05