Go to the documentation of this file.
42 #include <unordered_map>
44 #define NR_READADSD3500CCB 3
48 CameraItof(std::shared_ptr<aditof::DepthSensorInterface> depthSensor,
64 uint16_t abHeight,
bool advanceScaling,
65 bool useLogScaling)
override;
67 bool useLogScaling)
override;
75 std::shared_ptr<aditof::DepthSensorInterface>
getSensor()
override;
121 uint16_t
value)
override;
123 uint16_t &
value)
override;
125 int &imagerStatus)
override;
130 const std::vector<std::pair<uint8_t, uint8_t>> &sequence)
override;
132 bool useCacheValue =
false)
override;
140 const int16_t mode_in_use = -1)
override;
192 const std::map<std::string, std::string> &iniKeyValPairs);
266 #endif // CAMERA_ITOF_H
aditof::DepthSensorModeDetails m_modeDetailsCache
aditof::Status saveModuleCCB(const std::string &filepath) override
Save the CCB content which is obtained from module memory to a given file path.
aditof::Status enableXYZframe(bool enable) override
Enable the generation of a XYZ frame. The XYZ frame can be enabled or disabled through ....
bool m_enableDepthCompute
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.
aditof::Status adsd3500SetConfidenceThreshold(int threshold) override
Set the confidence threshold.
aditof::Status getDetails(aditof::CameraDetails &details) const override
Gets the current details of the camera.
aditof::Status adsd3500SetToggleMode(int mode) override
Enables or disables FSYNC toggle for ADSD3500.
std::vector< uint8_t > m_availableModes
Manipulates the underlying camera system.
aditof::Status setAdsd3500IniParams(const std::map< std::string, std::string > &iniKeyValPairs)
aditof::Status setControl(const std::string &control, const std::string &value) override
Sets a specific camera control.
aditof::ImagerType m_imagerType
std::map< std::string, std::string > m_ini_depth_map
int16_t m_enableMetaDatainAB
aditof::Status requestFrame(aditof::Frame *frame) override
Captures data from the camera and assigns it to the given frame.
std::unordered_map< std::string, std::string > m_controls
void freeConfigData(void)
Frees the calibration member variables created while loading the CCB contents.
aditof::Status readAdsd3500CCB(std::string &ccb)
Read the CCB from adsd3500 memory and store in output variable ccb.
aditof::Status adsd3500SetEnableMetadatainAB(uint16_t value) override
Set Enable Metadata in the AB frame.
aditof::Status getImagerType(aditof::ImagerType &imagerType) const override
Provides the type of the imager.
aditof::Status adsd3500GetJBLFGaussianSigma(uint16_t &value) override
Get JBLF Gaussian Sigma.
aditof::Status adsd3500IsCCBMsupported(bool &supported) override
Check whether CCB as master is supported or not.
aditof::CameraDetails m_details
aditof::Status adsd3500GetSensorTemperature(uint16_t &tmpValue) override
Get the sensor temperature.
aditof::Status adsd3500SetEnableTemperatureCompensation(uint16_t value) override
Set Enable Temperature Compensation.
aditof::Status readSerialNumber(std::string &serialNumber, bool useCacheValue=false) override
Read serial number from camera and update cache.
void configureSensorModeDetails()
aditof::Status setSensorConfiguration(const std::string &sensorConf) override
Set sensor configutation table.
aditof::Status adsd3500GetEnableMetadatainAB(uint16_t &value) override
Get state of Enable Metadata in the AB frame.
std::string m_netLinkTest
std::vector< aditof::DepthSensorModeDetails > m_availableSensorModeDetails
aditof::Status setFrameProcessParams(std::map< std::string, std::string > ¶ms) override
Set the Depth Compute Library ini parameters.
GLsizei const GLchar *const * string
Adsd3500Status
Status of the ADSD3500 sensor.
aditof::Status adsd3500SetRadialThresholdMin(int threshold) override
Set the radial threshold min.
aditof::Status adsd3500SetJBLFfilterEnableState(bool enable) override
Enable/disable the JBLF filter.
aditof::Status adsd3500SetJBLFABThreshold(uint16_t threshold) override
Get JBLF Max Edge Threshold.
int16_t m_mipiOutputSpeed
aditof::Status adsd3500GetStatus(int &chipStatus, int &imagerStatus) override
Returns the chip status.
std::map< int, std::map< std::string, std::string > > m_depth_params_map
aditof::Status enableDepthCompute(bool enable) override
Enable or disable the depth processing on the frames received from the sensor Must be called after ge...
aditof::Status adsd3500ToggleFsync() override
Toggles ADSD3500 FSYNC once if automated FSYNC is disabled.
aditof::Status normalizeABFrame(aditof::Frame *frame, bool advanceScaling, bool useLogScaling) override
Scale AB image with logarithmic base 10 in a Frame instance.
std::map< std::string, noArgCallable > m_noArgCallables
GLenum GLenum GLsizei const GLuint GLboolean enabled
aditof::Status adsd3500SetFrameRate(uint16_t fps) override
Set Frame Rate.
uint8_t m_depthBitsPerPixel
std::shared_ptr< aditof::DepthSensorInterface > m_depthSensor
aditof::Status adsd3500GetGenericTemplate(uint16_t reg, uint16_t &value) override
Generic ADSD3500 function for commands not defined in the SDK (yet)
aditof::Status adsd3500GetImagerErrorCode(uint16_t &errcode) override
Get error code from the imager.
std::map< std::string, FileData > m_depthINIDataMap
aditof::Status adsd3500SetGenericTemplate(uint16_t reg, uint16_t value) override
Generic ADSD3500 function for commands not defined in the SDK (yet)
aditof::Status retrieveDepthProcessParams()
aditof::Status adsd3500setEnableDynamicModeSwitching(bool en) override
Allows enabling or disabling the Dynamic Mode Switching. NOTE: This must be enabled before configurin...
std::pair< std::string, std::string > m_adsd3500FwGitHash
ImagerType
Types of imagers.
aditof::Status adsd3500SetVCSELDelay(uint16_t delay) override
Set the delay for VCSEL - ADSD3100 imager only.
int16_t m_enableEdgeConfidence
aditof::Status initialize(const std::string &configFilepath={}) override
Initialize the camera. This is required before performing any operation on the camera.
aditof::Status adsd3500GetJBLFfilterSize(int &size) override
Get the JBLF filter size.
int m_adsd3500FwVersionInt
aditof::Status getAvailableControls(std::vector< std::string > &controls) const override
Gets the camera's list of controls.
GLenum const GLfloat * params
aditof::Status getControl(const std::string &control, std::string &value) const override
Gets the value of a specific camera control.
aditof::Status saveModuleCFG(const std::string &filepath) const override
Save the CFG content which is obtained from module memory to a given file path.
aditof::Status adsd3500SetEnablePhaseInvalidation(uint16_t value) override
Set Enable Phase Invalidation.
Describes the properties of a camera.
aditof::Status getFrameProcessParams(std::map< std::string, std::string > ¶ms) override
Get the Depth Compute Library ini parameters.
aditof::Status adsd3500SetJBLFGaussianSigma(uint16_t value) override
Set JBLF Gaussian Sigma.
aditof::Status adsd3500ResetIniParamsForMode(const uint16_t mode) override
Reset the ini parameters from the chip and sets the ones stored in CCB.
aditof::Status adsd3500GetFirmwareVersion(std::string &fwVersion, std::string &fwHash) override
aditof::Status adsd3500GetConfidenceThreshold(int &threshold) override
Get the confidence threshold.
aditof::Status adsd3500GetVCSELDelay(uint16_t &delay) override
Get the delay for VCSEL - ADSD3100 imager only.
int16_t m_enableTempCompenstation
Status
Status of any operation that the TOF sdk performs.
std::string m_initConfigFilePath
aditof::Adsd3500Status m_adsd3500Status
aditof::Status adsd3500GetRadialThresholdMin(int &threshold) override
Get the radial threshold min.
aditof::Status adsd3500GetLaserTemperature(uint16_t &tmpValue) override
Get the laser temperature.
std::shared_ptr< aditof::DepthSensorInterface > getSensor() override
Gets the sensor of the camera. This gives direct access to low level configuration of the camera sens...
uint8_t m_confBitsPerPixel
bool m_tempSensorInitialized
aditof::Status adsd3500SetMIPIOutputSpeed(uint16_t speed) override
Set ADSD3500 MIPI output speed.
aditof::Status adsd3500GetMIPIOutputSpeed(uint16_t &speed) override
Get ADSD3500 MIPI output speed.
aditof::Status adsd3500GetRadialThresholdMax(int &threshold) override
Get the radial threshold max.
aditof::Status adsd3500GetTemperatureCompensationStatus(uint16_t &value) override
Get Temperature Compensation Status.
aditof::ADSDErrors m_adsdErrors
aditof::Status adsd3500SetEnableEdgeConfidence(uint16_t value) override
Set Enable Edge Confidence.
aditof::Status getAvailableModes(std::vector< uint8_t > &availableModes) const override
Returns all the modes that are supported by the camera.
std::string m_ccb_calibrationFile
Describes the type of entire frame that a depth sensor can capture and transmit.
std::string m_sensorFirmwareFile
aditof::Status start() override
Start the camera. This starts the streaming of data from the camera.
std::function< aditof::Status()> noArgCallable
TofiXYZDealiasData m_xyz_dealias_data[MAX_N_MODES+1]
aditof::Status adsd3500GetJBLFfilterEnableState(bool &enabled) override
Get the JBLF enabled state.
CameraItof(std::shared_ptr< aditof::DepthSensorInterface > depthSensor, const std::string &ubootVersion, const std::string &kernelVersion, const std::string &sdCardImageVersion, const std::string &netLinkTest)
aditof::Status setMode(const uint8_t &mode) override
Puts the camera into the given mode.
aditof::Status adsd3500SetJBLFfilterSize(int size) override
Set the JBLF filter size.
Error codes from the ADSD3500, ADSD3100, ADSD3030 Usage: Included with aditof/camera....
void dropFirstFrame(bool dropFrame) override
Allow drop first frame.
aditof::Status adsd3500GetFrameRate(uint16_t &fps) override
Get Frame Rate.
void normalizeABBuffer(uint16_t *abBuffer, uint16_t abWidth, uint16_t abHeight, bool advanceScaling, bool useLogScaling) override
Scale AB image with logarithmic base 10.
aditof::Status stop() override
Stop the camera. This makes the camera to stop streaming.
std::vector< std::pair< std::string, int32_t > > m_sensor_settings
GLsizei const GLfloat * value
aditof::Status saveDepthParamsToJsonFile(const std::string &savePathFile) override
Save ini file to json format.
void cleanupXYZtables()
Delete allocated tables for X, Y, Z.
aditof::Status adsd3500SetRadialThresholdMax(int threshold) override
Set the radial threshold max.
aditof::Status adsd3500GetABinvalidationThreshold(int &threshold) override
Get the AB invalidation threshold.
const std::map< ImagerType, std::string > imagerType
Types of imagers.
bool isConvertibleToDouble(const std::string &str)
Check if string can convert to double.
aditof::Status adsd3500SetABinvalidationThreshold(int threshold) override
Set the AB invalidation threshold.
std::map< std::string, std::string > m_iniKeyValPairs
aditof::Status adsd3500DisableCCBM(bool disable) override
Enable/disable ccb as master.
aditof::Status adsd3500SetJBLFExponentialTerm(uint16_t value) override
Set JBLF Exponential Term.
aditof::Status adsd3500SetJBLFMaxEdgeThreshold(uint16_t threshold) override
Set JBLF Max Edge Threshold.
std::vector< std::pair< uint8_t, uint8_t > > m_configDmsSequence
aditof::Status adsd3500UpdateFirmware(const std::string &filePath) override
Update the firmware of ADSD3500 with the content found in the specified file.
aditof::Status adsd3500GetJBLFExponentialTerm(uint16_t &value) override
Get JBLF Exponential Term.
aditof::Status adsds3500setDynamicModeSwitchingSequence(const std::vector< std::pair< uint8_t, uint8_t >> &sequence) override
Configures the sequence to be captured.
aditof::Status loadConfigData(void)
Opens the CCB file passed in as part of Json file using initialize(), and loads the calibration block...
libaditof
Author(s):
autogenerated on Wed May 21 2025 02:06:48