Public Member Functions | List of all members
aditof::Camera Class Referenceabstract

Manipulates the underlying camera system. More...

#include <camera.h>

Inheritance diagram for aditof::Camera:
Inheritance graph
[legend]

Public Member Functions

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

Detailed Description

Manipulates the underlying camera system.

Definition at line 54 of file camera.h.

Constructor & Destructor Documentation

◆ ~Camera()

virtual aditof::Camera::~Camera ( )
virtualdefault

Destructor.

Member Function Documentation

◆ adsd3500DisableCCBM()

virtual Status aditof::Camera::adsd3500DisableCCBM ( bool  disable)
pure virtual

Enable/disable ccb as master.

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

Implemented in CameraItof.

◆ adsd3500GetABinvalidationThreshold()

virtual Status aditof::Camera::adsd3500GetABinvalidationThreshold ( int &  threshold)
pure virtual

Get the AB invalidation threshold.

Parameters
[out]threshold
Returns
Status

Implemented in CameraItof.

◆ adsd3500GetConfidenceThreshold()

virtual Status aditof::Camera::adsd3500GetConfidenceThreshold ( int &  threshold)
pure virtual

Get the confidence threshold.

Parameters
[out]threshold
Returns
Status

Implemented in CameraItof.

◆ adsd3500GetEnableMetadatainAB()

virtual aditof::Status aditof::Camera::adsd3500GetEnableMetadatainAB ( uint16_t &  value)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500GetFirmwareVersion()

virtual Status aditof::Camera::adsd3500GetFirmwareVersion ( std::string fwVersion,
std::string fwHash 
)
pure virtual

Get the ASDSD3500 firmware version from the ADSD3500

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

Implemented in CameraItof.

◆ adsd3500GetFrameRate()

virtual Status aditof::Camera::adsd3500GetFrameRate ( uint16_t &  fps)
pure virtual

Get Frame Rate.

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

Implemented in CameraItof.

◆ adsd3500GetGenericTemplate()

virtual Status aditof::Camera::adsd3500GetGenericTemplate ( uint16_t  reg,
uint16_t &  value 
)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500GetImagerErrorCode()

virtual Status aditof::Camera::adsd3500GetImagerErrorCode ( uint16_t &  errcode)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500GetJBLFExponentialTerm()

virtual Status aditof::Camera::adsd3500GetJBLFExponentialTerm ( uint16_t &  value)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500GetJBLFfilterEnableState()

virtual Status aditof::Camera::adsd3500GetJBLFfilterEnableState ( bool &  enabled)
pure virtual

Get the JBLF enabled state.

Parameters
[out]enabled
Returns
Status

Implemented in CameraItof.

◆ adsd3500GetJBLFfilterSize()

virtual Status aditof::Camera::adsd3500GetJBLFfilterSize ( int &  size)
pure virtual

Get the JBLF filter size.

Parameters
[out]size
Returns
Status

Implemented in CameraItof.

◆ adsd3500GetJBLFGaussianSigma()

virtual Status aditof::Camera::adsd3500GetJBLFGaussianSigma ( uint16_t &  value)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500GetLaserTemperature()

virtual Status aditof::Camera::adsd3500GetLaserTemperature ( uint16_t &  tmpValue)
pure virtual

Get the laser temperature.

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

Implemented in CameraItof.

◆ adsd3500GetMIPIOutputSpeed()

virtual Status aditof::Camera::adsd3500GetMIPIOutputSpeed ( uint16_t &  speed)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500GetRadialThresholdMax()

virtual Status aditof::Camera::adsd3500GetRadialThresholdMax ( int &  threshold)
pure virtual

Get the radial threshold max.

Parameters
[out]threshold
Returns
Status

Implemented in CameraItof.

◆ adsd3500GetRadialThresholdMin()

virtual Status aditof::Camera::adsd3500GetRadialThresholdMin ( int &  threshold)
pure virtual

Get the radial threshold min.

Parameters
[out]threshold
Returns
Status

Implemented in CameraItof.

◆ adsd3500GetSensorTemperature()

virtual Status aditof::Camera::adsd3500GetSensorTemperature ( uint16_t &  tmpValue)
pure virtual

Get the sensor temperature.

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

Implemented in CameraItof.

◆ adsd3500GetStatus()

virtual Status aditof::Camera::adsd3500GetStatus ( int &  chipStatus,
int &  imagerStatus 
)
pure virtual

Returns the chip status.

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

Implemented in CameraItof.

◆ adsd3500GetTemperatureCompensationStatus()

virtual Status aditof::Camera::adsd3500GetTemperatureCompensationStatus ( uint16_t &  value)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500GetVCSELDelay()

virtual Status aditof::Camera::adsd3500GetVCSELDelay ( uint16_t &  delay)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500IsCCBMsupported()

virtual Status aditof::Camera::adsd3500IsCCBMsupported ( bool &  supported)
pure virtual

Check whether CCB as master is supported or not.

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

Implemented in CameraItof.

◆ adsd3500ResetIniParamsForMode()

virtual aditof::Status aditof::Camera::adsd3500ResetIniParamsForMode ( const uint16_t  mode)
pure virtual

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

Parameters
mode- Camera mode to be reset
Returns
Status

Implemented in CameraItof.

◆ adsd3500SetABinvalidationThreshold()

virtual Status aditof::Camera::adsd3500SetABinvalidationThreshold ( int  threshold)
pure virtual

Set the AB invalidation threshold.

Parameters
[in]threshold
Returns
Status

Implemented in CameraItof.

◆ adsd3500SetConfidenceThreshold()

virtual Status aditof::Camera::adsd3500SetConfidenceThreshold ( int  threshold)
pure virtual

Set the confidence threshold.

Parameters
[in]threshold
Returns
Status

Implemented in CameraItof.

◆ adsd3500setEnableDynamicModeSwitching()

virtual aditof::Status aditof::Camera::adsd3500setEnableDynamicModeSwitching ( bool  enable)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500SetEnableEdgeConfidence()

virtual Status aditof::Camera::adsd3500SetEnableEdgeConfidence ( uint16_t  value)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500SetEnableMetadatainAB()

virtual aditof::Status aditof::Camera::adsd3500SetEnableMetadatainAB ( uint16_t  value)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500SetEnablePhaseInvalidation()

virtual Status aditof::Camera::adsd3500SetEnablePhaseInvalidation ( uint16_t  value)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500SetEnableTemperatureCompensation()

virtual Status aditof::Camera::adsd3500SetEnableTemperatureCompensation ( uint16_t  value)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500SetFrameRate()

virtual Status aditof::Camera::adsd3500SetFrameRate ( uint16_t  fps)
pure virtual

Set Frame Rate.

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

Implemented in CameraItof.

◆ adsd3500SetGenericTemplate()

virtual Status aditof::Camera::adsd3500SetGenericTemplate ( uint16_t  reg,
uint16_t  value 
)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500SetJBLFABThreshold()

virtual Status aditof::Camera::adsd3500SetJBLFABThreshold ( uint16_t  threshold)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500SetJBLFExponentialTerm()

virtual Status aditof::Camera::adsd3500SetJBLFExponentialTerm ( uint16_t  value)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500SetJBLFfilterEnableState()

virtual Status aditof::Camera::adsd3500SetJBLFfilterEnableState ( bool  enable)
pure virtual

Enable/disable the JBLF filter.

Parameters
[in]enable
Returns
Status

Implemented in CameraItof.

◆ adsd3500SetJBLFfilterSize()

virtual Status aditof::Camera::adsd3500SetJBLFfilterSize ( int  size)
pure virtual

Set the JBLF filter size.

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

Implemented in CameraItof.

◆ adsd3500SetJBLFGaussianSigma()

virtual Status aditof::Camera::adsd3500SetJBLFGaussianSigma ( uint16_t  value)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500SetJBLFMaxEdgeThreshold()

virtual Status aditof::Camera::adsd3500SetJBLFMaxEdgeThreshold ( uint16_t  threshold)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500SetMIPIOutputSpeed()

virtual Status aditof::Camera::adsd3500SetMIPIOutputSpeed ( uint16_t  speed)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500SetRadialThresholdMax()

virtual Status aditof::Camera::adsd3500SetRadialThresholdMax ( int  threshold)
pure virtual

Set the radial threshold max.

Parameters
[in]threshold
Returns
Status

Implemented in CameraItof.

◆ adsd3500SetRadialThresholdMin()

virtual Status aditof::Camera::adsd3500SetRadialThresholdMin ( int  threshold)
pure virtual

Set the radial threshold min.

Parameters
[in]threshold
Returns
Status

Implemented in CameraItof.

◆ adsd3500SetToggleMode()

virtual Status aditof::Camera::adsd3500SetToggleMode ( int  mode)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500SetVCSELDelay()

virtual Status aditof::Camera::adsd3500SetVCSELDelay ( uint16_t  delay)
pure virtual

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

Implemented in CameraItof.

◆ adsd3500ToggleFsync()

virtual Status aditof::Camera::adsd3500ToggleFsync ( )
pure virtual

Toggles ADSD3500 FSYNC once if automated FSYNC is disabled.

Returns
Status

Implemented in CameraItof.

◆ adsd3500UpdateFirmware()

virtual Status aditof::Camera::adsd3500UpdateFirmware ( const std::string fwFilePath)
pure virtual

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

Implemented in CameraItof.

◆ adsds3500setDynamicModeSwitchingSequence()

virtual aditof::Status aditof::Camera::adsds3500setDynamicModeSwitchingSequence ( const std::vector< std::pair< uint8_t, uint8_t >> &  sequence)
pure virtual

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

Implemented in CameraItof.

◆ dropFirstFrame()

virtual void aditof::Camera::dropFirstFrame ( bool  dropFrame)
pure virtual

Allow drop first frame.

Parameters
dropFrame- Drop the first frame if true
Returns
void

Implemented in CameraItof.

◆ enableDepthCompute()

virtual Status aditof::Camera::enableDepthCompute ( bool  enable)
pure virtual

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

Implemented in CameraItof.

◆ enableXYZframe()

virtual Status aditof::Camera::enableXYZframe ( bool  enable)
pure virtual

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

Implemented in CameraItof.

◆ getAvailableControls()

virtual Status aditof::Camera::getAvailableControls ( std::vector< std::string > &  controls) const
pure virtual

Gets the camera's list of controls.

Parameters
[out]controls
Returns
Status

Implemented in CameraItof.

◆ getAvailableModes()

virtual Status aditof::Camera::getAvailableModes ( std::vector< uint8_t > &  availableModes) const
pure virtual

Returns all the modes that are supported by the camera.

Parameters
[out]availableModes
Returns
Status

Implemented in CameraItof.

◆ getControl()

virtual Status aditof::Camera::getControl ( const std::string control,
std::string value 
) const
pure virtual

Gets the value of a specific camera control.

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

Implemented in CameraItof.

◆ getDetails()

virtual Status aditof::Camera::getDetails ( CameraDetails details) const
pure virtual

Gets the current details of the camera.

Parameters
[out]details
Returns
Status

Implemented in CameraItof.

◆ getFrameProcessParams()

virtual Status aditof::Camera::getFrameProcessParams ( std::map< std::string, std::string > &  params)
pure virtual

Get the Depth Compute Library ini parameters.

Parameters
params- a dictionary of parameters
Returns
Status

Implemented in CameraItof.

◆ getImagerType()

virtual Status aditof::Camera::getImagerType ( ImagerType imagerType) const
pure virtual

Provides the type of the imager.

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

Implemented in CameraItof.

◆ getSensor()

virtual std::shared_ptr<DepthSensorInterface> aditof::Camera::getSensor ( )
pure virtual

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

Returns
std::shared_ptr<DepthSensorInterface>

Implemented in CameraItof.

◆ initialize()

virtual Status aditof::Camera::initialize ( const std::string configFilepath = {})
pure virtual

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

Implemented in CameraItof.

◆ loadDepthParamsFromJsonFile()

virtual aditof::Status aditof::Camera::loadDepthParamsFromJsonFile ( const std::string pathFileloadDepthParamsFromJsonFile,
const int16_t  mode_in_use = -1 
)
pure virtual

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

Implemented in CameraItof.

◆ normalizeABBuffer()

virtual void aditof::Camera::normalizeABBuffer ( uint16_t *  abBuffer,
uint16_t  abWidth,
uint16_t  abHeight,
bool  advanceScaling,
bool  useLogScaling 
)
pure virtual

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

Implemented in CameraItof.

◆ normalizeABFrame()

virtual aditof::Status aditof::Camera::normalizeABFrame ( aditof::Frame frame,
bool  advanceScaling,
bool  useLogScaling 
)
pure virtual

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

Implemented in CameraItof.

◆ readSerialNumber()

virtual Status aditof::Camera::readSerialNumber ( std::string serialNumber,
bool  useCacheValue = false 
)
pure virtual

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

Implemented in CameraItof.

◆ requestFrame()

virtual Status aditof::Camera::requestFrame ( Frame frame)
pure virtual

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

Implemented in CameraItof.

◆ saveDepthParamsToJsonFile()

virtual aditof::Status aditof::Camera::saveDepthParamsToJsonFile ( const std::string savePathFile)
pure virtual

Save ini file to json format.

Parameters
savePathFile- Path to save json file
Returns
Status

Implemented in CameraItof.

◆ saveModuleCCB()

virtual Status aditof::Camera::saveModuleCCB ( const std::string filepath)
pure virtual

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

Implemented in CameraItof.

◆ saveModuleCFG()

virtual Status aditof::Camera::saveModuleCFG ( const std::string filepath) const
pure virtual

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

Implemented in CameraItof.

◆ setControl()

virtual Status aditof::Camera::setControl ( const std::string control,
const std::string value 
)
pure virtual

Sets a specific camera control.

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

Implemented in CameraItof.

◆ setFrameProcessParams()

virtual Status aditof::Camera::setFrameProcessParams ( std::map< std::string, std::string > &  params)
pure virtual

Set the Depth Compute Library ini parameters.

Parameters
params- a dictionary of parameters
Returns
Status

Implemented in CameraItof.

◆ setMode()

virtual Status aditof::Camera::setMode ( const uint8_t &  mode)
pure virtual

Puts the camera into the given mode.

Parameters
mode- The mode of the camera
Returns
Status

Implemented in CameraItof.

◆ setSensorConfiguration()

virtual aditof::Status aditof::Camera::setSensorConfiguration ( const std::string sensorConf)
pure virtual

Set sensor configutation table.

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

Implemented in CameraItof.

◆ start()

virtual Status aditof::Camera::start ( )
pure virtual

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

Returns
Status

Implemented in CameraItof.

◆ stop()

virtual Status aditof::Camera::stop ( )
pure virtual

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

Returns
Status

Implemented in CameraItof.


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


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