#include <camera_itof.h>
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 > ¶ms) 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::DepthSensorInterface > | getSensor () 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 > ¶ms) 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 () | |
![]() | |
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) |
Definition at line 46 of file camera_itof.h.
|
private |
Definition at line 205 of file camera_itof.h.
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 | ( | ) |
Definition at line 115 of file camera_itof.cpp.
|
overridevirtual |
Enable/disable ccb as master.
[in] | disable | - set to: 1 - disable, 0 - enable |
Implements aditof::Camera.
Definition at line 1856 of file camera_itof.cpp.
|
overridevirtual |
Get the AB invalidation threshold.
[out] | threshold |
Implements aditof::Camera.
Definition at line 1691 of file camera_itof.cpp.
|
overridevirtual |
Get the confidence threshold.
[out] | threshold |
Implements aditof::Camera.
Definition at line 1700 of file camera_itof.cpp.
|
overridevirtual |
Get state of Enable Metadata in the AB frame.
[out] | value | - See "Get Output Metadata in AB Frame status" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1840 of file camera_itof.cpp.
|
overridevirtual |
Get the ASDSD3500 firmware version from the ADSD3500
[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.
|
overridevirtual |
Get Frame Rate.
[out] | fps | - See "Get Frame Rate" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1795 of file camera_itof.cpp.
|
overridevirtual |
Generic ADSD3500 function for commands not defined in the SDK (yet)
[in] | reg | - 16-bit ADSD3500 register |
[out] | value | - 16-bit value read from the register |
Implements aditof::Camera.
Definition at line 1850 of file camera_itof.cpp.
|
overridevirtual |
Get error code from the imager.
[out] | errcode | - See "Get Imager Error Code" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1754 of file camera_itof.cpp.
|
overridevirtual |
Get JBLF Exponential Term.
[out] | value | - See "Get JBLF Exponential Term" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1790 of file camera_itof.cpp.
|
overridevirtual |
Get the JBLF enabled state.
[out] | enabled |
Implements aditof::Camera.
Definition at line 1709 of file camera_itof.cpp.
|
overridevirtual |
Get the JBLF filter size.
[out] | size |
Implements aditof::Camera.
Definition at line 1720 of file camera_itof.cpp.
|
overridevirtual |
Get JBLF Gaussian Sigma.
[out] | value | - See "Get JBLF Gaussian Sigma" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1780 of file camera_itof.cpp.
|
overridevirtual |
Get the laser temperature.
[out] | tmpValue | - Values in Celsius degree |
Implements aditof::Camera.
Definition at line 1933 of file camera_itof.cpp.
|
overridevirtual |
Get ADSD3500 MIPI output speed.
[out] | speed | - See "Get MIPI Output Speed" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1749 of file camera_itof.cpp.
|
overridevirtual |
Get the radial threshold max.
[out] | threshold |
Implements aditof::Camera.
Definition at line 1739 of file camera_itof.cpp.
|
overridevirtual |
Get the radial threshold min.
[out] | threshold |
Implements aditof::Camera.
Definition at line 1729 of file camera_itof.cpp.
|
overridevirtual |
Get the sensor temperature.
[out] | tmpValue | - Values in Celsius degree |
Implements aditof::Camera.
Definition at line 1916 of file camera_itof.cpp.
|
overridevirtual |
Returns the chip status.
[out] | chipStatus | - chip status (error) value |
[out] | imagerStatus | - imager status (error) value |
Implements aditof::Camera.
Definition at line 1880 of file camera_itof.cpp.
|
overridevirtual |
Get Temperature Compensation Status.
[out] | value | - See "Get Temperature Compensation Status" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1822 of file camera_itof.cpp.
|
overridevirtual |
Get the delay for VCSEL - ADSD3100 imager only.
[out] | delay | - See "Get VCSEL Delay" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1763 of file camera_itof.cpp.
|
overridevirtual |
Check whether CCB as master is supported or not.
[out] | supported | - Will be set to true in case CCBM is supported |
Implements aditof::Camera.
Definition at line 1860 of file camera_itof.cpp.
|
overridevirtual |
Reset the ini parameters from the chip and sets the ones stored in CCB.
mode | - Camera mode to be reset |
Implements aditof::Camera.
Definition at line 564 of file camera_itof.cpp.
|
overridevirtual |
Set the AB invalidation threshold.
[in] | threshold |
Implements aditof::Camera.
Definition at line 1687 of file camera_itof.cpp.
|
overridevirtual |
Set the confidence threshold.
[in] | threshold |
Implements aditof::Camera.
Definition at line 1697 of file camera_itof.cpp.
|
overridevirtual |
Allows enabling or disabling the Dynamic Mode Switching. NOTE: This must be enabled before configuring the sequence!
[in] | enable | - Set to true to enable and false to disable |
Implements aditof::Camera.
Definition at line 2112 of file camera_itof.cpp.
|
overridevirtual |
Set Enable Edge Confidence.
[in] | value | - See "Set Enable Edge Confidence" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1817 of file camera_itof.cpp.
|
overridevirtual |
Set Enable Metadata in the AB frame.
[in] | value | - See "Enable/Disable Output Metadata in AB Frame" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1836 of file camera_itof.cpp.
|
overridevirtual |
Set Enable Phase Invalidation.
[out] | value | - See "Set Enable Phase Invalidation" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1827 of file camera_itof.cpp.
|
overridevirtual |
Set Enable Temperature Compensation.
[out] | value | - See "Set Enable Temperature Compensation" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1832 of file camera_itof.cpp.
|
overridevirtual |
Set Frame Rate.
[out] | fps | - See "Set Frame Rate" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1800 of file camera_itof.cpp.
|
overridevirtual |
Generic ADSD3500 function for commands not defined in the SDK (yet)
[in] | reg | - 16-bit ADSD3500 register |
[in] | value | - 16-bit value to write to the register |
Implements aditof::Camera.
Definition at line 1845 of file camera_itof.cpp.
|
overridevirtual |
Get JBLF Max Edge Threshold.
[out] | threshold | - See "Get JBLF Max Edge Threshold" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1772 of file camera_itof.cpp.
|
overridevirtual |
Set JBLF Exponential Term.
[in] | value | - See "Set JBLF Exponential Term" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1786 of file camera_itof.cpp.
|
overridevirtual |
Enable/disable the JBLF filter.
[in] | enable |
Implements aditof::Camera.
Definition at line 1706 of file camera_itof.cpp.
|
overridevirtual |
Set the JBLF filter size.
[in] | size | - Supported sizes are: 3, 5, 7 |
Implements aditof::Camera.
Definition at line 1717 of file camera_itof.cpp.
|
overridevirtual |
Set JBLF Gaussian Sigma.
[in] | value | - See "Set JBLF Gaussian Sigma" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1776 of file camera_itof.cpp.
|
overridevirtual |
Set JBLF Max Edge Threshold.
[in] | threshold | - See "Set JBLF Max Edge Threshold" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1768 of file camera_itof.cpp.
|
overridevirtual |
Set ADSD3500 MIPI output speed.
[in] | speed | - See "Set MIPI Output Speed" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1745 of file camera_itof.cpp.
|
overridevirtual |
Set the radial threshold max.
[in] | threshold |
Implements aditof::Camera.
Definition at line 1735 of file camera_itof.cpp.
|
overridevirtual |
Set the radial threshold min.
[in] | threshold |
Implements aditof::Camera.
Definition at line 1726 of file camera_itof.cpp.
|
overridevirtual |
Enables or disables FSYNC toggle for ADSD3500.
[in] | mode | - 2 = Fsync pin set as HiZ ; 1 = Toggle at user specified framerate ; 0 = Toggle controlled via adsd3500ToggleFsync ; |
Implements aditof::Camera.
Definition at line 1616 of file camera_itof.cpp.
|
overridevirtual |
Set the delay for VCSEL - ADSD3100 imager only.
[in] | delay | - See "Set VCSEL Delay" at https://wiki.analog.com/resources/eval/user-guides/eval-adtf3175x-adsd3500 |
Implements aditof::Camera.
Definition at line 1759 of file camera_itof.cpp.
|
overridevirtual |
Toggles ADSD3500 FSYNC once if automated FSYNC is disabled.
Implements aditof::Camera.
Definition at line 1636 of file camera_itof.cpp.
|
overridevirtual |
Update the firmware of ADSD3500 with the content found in the specified file.
[in] | fwFilePath | - A path to a file (including file name and extension) where the firmware for adsd3500 is stored. |
Implements aditof::Camera.
Definition at line 1003 of file camera_itof.cpp.
|
overridevirtual |
Configures the sequence to be captured.
[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!
Implements aditof::Camera.
Definition at line 2117 of file camera_itof.cpp.
|
private |
Delete allocated tables for X, Y, Z.
Definition at line 2091 of file camera_itof.cpp.
|
private |
Configure the sensor with various settings that affect the frame type.
Definition at line 1231 of file camera_itof.cpp.
|
overridevirtual |
Allow drop first frame.
dropFrame | - Drop the first frame if true |
Implements aditof::Camera.
Definition at line 1607 of file camera_itof.cpp.
|
overridevirtual |
Enable or disable the depth processing on the frames received from the sensor Must be called after getFrame() where the depth processing happens.
[in] | enable | - set to true to enable depth processing. Set to false otherwise. |
Implements aditof::Camera.
Definition at line 984 of file camera_itof.cpp.
|
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.
[in] | enable | - set to true to enable the generation of XYZ, set to false otherwise. |
Implements aditof::Camera.
Definition at line 977 of file camera_itof.cpp.
Frees the calibration member variables created while loading the CCB contents.
Definition at line 889 of file camera_itof.cpp.
|
overridevirtual |
Gets the camera's list of controls.
[out] | controls |
Implements aditof::Camera.
Definition at line 808 of file camera_itof.cpp.
|
overridevirtual |
Returns all the modes that are supported by the camera.
[out] | availableModes |
Implements aditof::Camera.
Definition at line 569 of file camera_itof.cpp.
|
overridevirtual |
Gets the value of a specific camera control.
[in] | control | - Control name |
[out] | value | - Control value |
Implements aditof::Camera.
Definition at line 840 of file camera_itof.cpp.
|
overridevirtual |
Gets the current details of the camera.
[out] | details |
Implements aditof::Camera.
Definition at line 794 of file camera_itof.cpp.
|
overridevirtual |
Get the Depth Compute Library ini parameters.
params | - a dictionary of parameters |
Implements aditof::Camera.
Definition at line 538 of file camera_itof.cpp.
|
overridevirtual |
Provides the type of the imager.
[out] | imagerType | - Will be set with the imager type |
Implements aditof::Camera.
Definition at line 2106 of file camera_itof.cpp.
|
overridevirtual |
Gets the sensor of the camera. This gives direct access to low level configuration of the camera sensor.
Implements aditof::Camera.
Definition at line 803 of file camera_itof.cpp.
|
overridevirtual |
Initialize the camera. This is required before performing any operation on the camera.
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. |
Implements aditof::Camera.
Definition at line 121 of file camera_itof.cpp.
|
private |
Check if string can convert to double.
Definition at line 1597 of file camera_itof.cpp.
|
private |
Opens the CCB file passed in as part of Json file using initialize(), and loads the calibration blocks into member variable.
Definition at line 855 of file camera_itof.cpp.
|
overridevirtual |
Load adsd parameters from json file. Need setMode to apply.
pathFileloadDepthParamsFromJsonFile | - Path to load from json file |
mode_in_use | - Specify to read details for a specifc mode |
Implements aditof::Camera.
Definition at line 1457 of file camera_itof.cpp.
|
overridevirtual |
Scale AB image with logarithmic base 10.
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 |
Implements aditof::Camera.
Definition at line 681 of file camera_itof.cpp.
|
overridevirtual |
Scale AB image with logarithmic base 10 in a Frame instance.
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 |
Implements aditof::Camera.
Definition at line 763 of file camera_itof.cpp.
|
private |
Read the CCB from adsd3500 memory and store in output variable ccb.
[out] | ccb | - where to store the CCB content |
Definition at line 1144 of file camera_itof.cpp.
|
overridevirtual |
Read serial number from camera and update cache.
[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 |
Implements aditof::Camera.
Definition at line 905 of file camera_itof.cpp.
|
overridevirtual |
Captures data from the camera and assigns it to the given frame.
frame | - The frame to which the camera data should be assign |
Implements aditof::Camera.
Definition at line 581 of file camera_itof.cpp.
|
private |
Reads the depth process parameters from camera
Definition at line 1345 of file camera_itof.cpp.
|
overridevirtual |
Save ini file to json format.
savePathFile | - Path to save json file |
Implements aditof::Camera.
Definition at line 1367 of file camera_itof.cpp.
|
overridevirtual |
Save the CCB content which is obtained from module memory to a given file path.
[in] | filepath | - A path to a file (including file name and extension) where the CCB should be stored. |
Implements aditof::Camera.
Definition at line 939 of file camera_itof.cpp.
|
overridevirtual |
Save the CFG content which is obtained from module memory to a given file path.
[in] | filepath | - A path to a file (including file name and extension) where the CFG should be stored. |
Implements aditof::Camera.
Definition at line 967 of file camera_itof.cpp.
|
private |
Configure ADSD3500 with ini parameters
[in] | iniKeyValPairs | - ini parameteres to use |
Definition at line 1951 of file camera_itof.cpp.
|
overridevirtual |
Sets a specific camera control.
[in] | control | - Control name |
[in] | value | - Control value |
Implements aditof::Camera.
Definition at line 821 of file camera_itof.cpp.
|
overridevirtual |
Set the Depth Compute Library ini parameters.
params | - a dictionary of parameters |
Implements aditof::Camera.
Definition at line 548 of file camera_itof.cpp.
|
overridevirtual |
Puts the camera into the given mode.
mode | - The mode of the camera |
Implements aditof::Camera.
Definition at line 328 of file camera_itof.cpp.
|
overridevirtual |
Set sensor configutation table.
sensorConf | - Configuration table name string like e.g. standard, standardraw, custom and customraw |
Implements aditof::Camera.
Definition at line 1612 of file camera_itof.cpp.
|
overridevirtual |
Start the camera. This starts the streaming of data from the camera.
Implements aditof::Camera.
Definition at line 302 of file camera_itof.cpp.
|
overridevirtual |
Stop the camera. This makes the camera to stop streaming.
Implements aditof::Camera.
Definition at line 315 of file camera_itof.cpp.
|
private |
Definition at line 235 of file camera_itof.h.
|
private |
Definition at line 233 of file camera_itof.h.
|
private |
Definition at line 217 of file camera_itof.h.
|
private |
Definition at line 216 of file camera_itof.h.
|
private |
Definition at line 252 of file camera_itof.h.
|
private |
Definition at line 253 of file camera_itof.h.
|
private |
Definition at line 256 of file camera_itof.h.
|
private |
Definition at line 211 of file camera_itof.h.
|
private |
Definition at line 241 of file camera_itof.h.
|
private |
Definition at line 240 of file camera_itof.h.
Definition at line 221 of file camera_itof.h.
|
private |
Definition at line 244 of file camera_itof.h.
|
private |
Definition at line 229 of file camera_itof.h.
|
private |
Definition at line 236 of file camera_itof.h.
|
private |
Definition at line 263 of file camera_itof.h.
|
private |
Definition at line 209 of file camera_itof.h.
|
private |
Definition at line 232 of file camera_itof.h.
|
private |
Definition at line 234 of file camera_itof.h.
|
private |
Definition at line 223 of file camera_itof.h.
|
private |
Definition at line 224 of file camera_itof.h.
|
private |
Definition at line 208 of file camera_itof.h.
|
private |
Definition at line 207 of file camera_itof.h.
|
private |
Definition at line 213 of file camera_itof.h.
|
private |
Definition at line 214 of file camera_itof.h.
|
private |
Definition at line 261 of file camera_itof.h.
|
private |
Definition at line 262 of file camera_itof.h.
|
private |
Definition at line 258 of file camera_itof.h.
|
private |
Definition at line 249 of file camera_itof.h.
|
private |
Definition at line 248 of file camera_itof.h.
|
private |
Definition at line 247 of file camera_itof.h.
|
private |
Definition at line 245 of file camera_itof.h.
|
private |
Definition at line 255 of file camera_itof.h.
|
private |
Definition at line 260 of file camera_itof.h.
|
private |
Definition at line 230 of file camera_itof.h.
|
private |
Definition at line 231 of file camera_itof.h.
|
private |
Definition at line 250 of file camera_itof.h.
|
private |
Definition at line 259 of file camera_itof.h.
|
private |
Definition at line 218 of file camera_itof.h.
|
private |
Definition at line 226 of file camera_itof.h.
|
private |
Definition at line 246 of file camera_itof.h.
|
private |
Definition at line 242 of file camera_itof.h.
|
private |
Definition at line 254 of file camera_itof.h.
|
private |
Definition at line 219 of file camera_itof.h.
|
private |
Definition at line 210 of file camera_itof.h.
|
private |
Definition at line 239 of file camera_itof.h.
|
private |
Definition at line 243 of file camera_itof.h.
|
private |
Definition at line 228 of file camera_itof.h.
|
private |
Definition at line 215 of file camera_itof.h.
|
private |
Definition at line 225 of file camera_itof.h.
|
private |
Definition at line 237 of file camera_itof.h.
|
private |
Definition at line 238 of file camera_itof.h.
|
private |
Definition at line 257 of file camera_itof.h.