Go to the documentation of this file.
39 #include <unordered_map>
88 public std::enable_shared_from_this<Adsd3500Sensor> {
122 unsigned int usDelay = 0)
override;
125 unsigned int usDelay = 0)
override;
128 uint16_t payload_len)
override;
130 uint16_t payload_len)
override;
133 uint16_t payload_len)
override;
142 int &imagerStatus)
override;
154 const struct v4l2_buffer &
buf)
override;
161 uint8_t *calData, uint16_t calDataLength)
override;
168 const std::map<std::string, std::string> &
params)
override;
178 uint32_t &buf_data_len,
179 const struct v4l2_buffer &
buf,
186 const void *p_tofi_cal_config);
188 const void *p_tofi_cal_config);
192 std::map<std::string, std::string> &
params);
214 std::unordered_map<void *, aditof::SensorInterruptCallback>
std::vector< aditof::DepthSensorModeDetails > m_availableModes
BufferProcessor * m_bufferProcessor
virtual aditof::Status setDepthComputeParams(const std::map< std::string, std::string > ¶ms) override
Set ini parameters for Depth Compute library.
aditof::ConnectionType m_hostConnectionType
aditof::Status convertIniParams(iniFileStruct &iniStruct, std::string &inistr)
virtual aditof::Status adsd3500_get_status(int &chipStatus, int &imagerStatus) override
Returns the chip status.
virtual aditof::Status getDeviceFileDescriptor(int &fileDescriptor) override
aditof::Status adsd3500InterruptHandler(int signalValue)
GLuint const GLchar * name
virtual aditof::Status getAvailableControls(std::vector< std::string > &controls) const override
Gets the sensors's list of controls.
virtual aditof::Status getDepthComputeParams(std::map< std::string, std::string > ¶ms) override
Get ini parameters for Depth Compute library.
Provides details about the device.
aditof::Status getDefaultIniParamsForMode(const std::string &imager, const std::string &mode, std::map< std::string, std::string > ¶ms)
virtual aditof::Status initTargetDepthCompute(uint8_t *iniFile, uint16_t iniFileLength, uint8_t *calData, uint16_t calDataLength) override
Get the name of the sensor.
std::unordered_map< std::string, std::string > m_controls
uint8_t m_capturesPerFrame
aditof::Status getInternalBufferPrivate(uint8_t **buffer, uint32_t &buf_data_len, const struct v4l2_buffer &buf, struct VideoDev *dev=nullptr)
virtual aditof::Status open() override
Open the communication channels with the hardware.
uint16_t jblfGaussianSigma
virtual aditof::Status getModeDetails(const uint8_t &mode, aditof::DepthSensorModeDetails &details) override
Returns details of specified mode.
virtual aditof::Status setMode(const aditof::DepthSensorModeDetails &type) override
Set the sensor frame mode to the given type.
GLsizei const GLchar *const * string
aditof::Status waitForBufferPrivate(struct VideoDev *dev=nullptr)
virtual aditof::Status adsd3500_read_payload_cmd(uint32_t cmd, uint8_t *readback_data, uint16_t payload_len) override
Send a read command to adsd3500. This will perform a burst read making it useful for reading chunks o...
virtual aditof::Status getName(std::string &name) const override
Get the name of the sensor.
Adsd3500Status
Status of the ADSD3500 sensor.
virtual aditof::Status start() override
Start the streaming of data from the sensor.
virtual aditof::Status getInternalBuffer(uint8_t **buffer, uint32_t &buf_data_len, const struct v4l2_buffer &buf) override
aditof::Status createIniParams(std::vector< iniFileStruct > &iniFileStructList)
aditof::Status mergeIniParams(std::vector< iniFileStruct > &iniFileStructList)
std::string m_driverSubPath
Adsd3500Sensor(const std::string &driverPath, const std::string &driverSubPath, const std::string &captureDev)
virtual aditof::Status getDetails(aditof::SensorDetails &details) const override
Get a structure that contains information about the instance of the sensor.
virtual aditof::Status adsd3500_read_payload(uint8_t *payload, uint16_t payload_len) override
Reads a chunk of data from adsd3500. This will perform a burst read making it useful for reading chun...
uint16_t jblfExponentialTerm
aditof::Status enqueueInternalBufferPrivate(struct v4l2_buffer &buf, struct VideoDev *dev=nullptr)
virtual aditof::Status enqueueInternalBuffer(struct v4l2_buffer &buf) override
aditof::Status setIniParamsImpl(void *p_config_params, int params_group, const void *p_tofi_cal_config)
virtual aditof::Status adsd3500_register_interrupt_callback(aditof::SensorInterruptCallback &cb) override
Register a function to be called when a ADSD3500 interrupt occurs.
GLenum const GLfloat * params
std::string m_sensorConfiguration
aditof::SensorDetails m_sensorDetails
GLenum GLuint GLenum GLsizei const GLchar * buf
aditof::Status dequeueInternalBufferPrivate(struct v4l2_buffer &buf, struct VideoDev *dev=nullptr)
ConnectionType
Types of connections.
Status
Status of any operation that the TOF sdk performs.
std::vector< iniFileStruct > m_iniFileStructList
bool m_depthComputeOnTarget
Provides access to the low level functionality of the camera sensor. This includes sensor configurati...
aditof::Adsd3500ModeSelector m_modeSelector
virtual aditof::Status setSensorConfiguration(const std::string &sensorConf) override
Set sensor configutation table.
virtual aditof::Status adsd3500_write_payload(uint8_t *payload, uint16_t payload_len) override
Send a chunk of data (payload) to adsd3500. This will perform a burst write making it useful for writ...
virtual aditof::Status stop() override
Stop the sensor data stream.
aditof::Adsd3500Status convertIdToAdsd3500Status(int status)
aditof::Status queryAdsd3500()
virtual aditof::Status setControl(const std::string &control, const std::string &value) override
Sets a specific sensor control.
aditof::Status getIniParamsImpl(void *p_config_params, int params_group, const void *p_tofi_cal_config)
virtual aditof::Status setHostConnectionType(std::string &connectionType) override
Set the host connection type for target sdk.
virtual aditof::Status getHandle(void **handle) override
Gets a handle to be used by other devices such as Storage, Temperature, etc. This handle will allow t...
Interface for operations on v4l buffer such as enquing and dequeing.
Describes the type of entire frame that a depth sensor can capture and transmit.
virtual aditof::Status getControl(const std::string &control, std::string &value) const override
Gets the value of a specific sensor control.
aditof::Status writeConfigBlock(const uint32_t offset)
virtual aditof::Status waitForBuffer() override
virtual aditof::Status adsd3500_reset() override
Reset adsd3500 chip.
virtual aditof::Status adsd3500_read_cmd(uint16_t cmd, uint16_t *data, unsigned int usDelay=0) override
Send a read command to adsd3500.
GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const GLvoid * data
virtual aditof::Status getFrame(uint16_t *buffer) override
Request a frame from the sensor.
aditof::Status getIniParamsArrayForMode(int mode, std::string &iniStr) override
Get ini parameters for Depth Compute library as string.
GLsizei const GLfloat * value
virtual aditof::Status adsd3500_unregister_interrupt_callback(aditof::SensorInterruptCallback &cb) override
Unregister a function registered with adsd3500_register_interrupt_callback.
std::vector< IniTableEntry > m_ccbmINIContent
virtual aditof::Status adsd3500_write_cmd(uint16_t cmd, uint16_t data, unsigned int usDelay=0) override
Send a write command to adsd3500.
virtual aditof::Status getAvailableModes(std::vector< uint8_t > &modes) override
Return all modes that are supported by the sensor.
std::unordered_map< void *, aditof::SensorInterruptCallback > m_interruptCallbackMap
virtual aditof::Status dequeueInternalBuffer(struct v4l2_buffer &buf) override
aditof::Adsd3500Status m_adsd3500Status
std::unique_ptr< ImplData > m_implData
virtual aditof::Status adsd3500_write_payload_cmd(uint32_t cmd, uint8_t *payload, uint16_t payload_len) override
Send a write command to adsd3500. This will perform a burst write making it useful for writing chunks...
std::function< void(Adsd3500Status)> SensorInterruptCallback
Callback for sensor interrupts.
libaditof
Author(s):
autogenerated on Wed May 21 2025 02:06:47