#include <adsd3500_sensor.h>
Classes | |
struct | ImplData |
Public Member Functions | |
virtual aditof::Status | adsd3500_get_status (int &chipStatus, int &imagerStatus) override |
Returns the chip status. More... | |
virtual aditof::Status | adsd3500_read_cmd (uint16_t cmd, uint16_t *data, unsigned int usDelay=0) override |
Send a read command to adsd3500. More... | |
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 chunks of data. More... | |
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 of data. More... | |
virtual aditof::Status | adsd3500_register_interrupt_callback (aditof::SensorInterruptCallback &cb) override |
Register a function to be called when a ADSD3500 interrupt occurs. More... | |
virtual aditof::Status | adsd3500_reset () override |
Reset adsd3500 chip. More... | |
virtual aditof::Status | adsd3500_unregister_interrupt_callback (aditof::SensorInterruptCallback &cb) override |
Unregister a function registered with adsd3500_register_interrupt_callback. More... | |
virtual aditof::Status | adsd3500_write_cmd (uint16_t cmd, uint16_t data, unsigned int usDelay=0) override |
Send a write command to adsd3500. More... | |
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 writing chunks of data. More... | |
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 of data. More... | |
aditof::Status | adsd3500InterruptHandler (int signalValue) |
Adsd3500Sensor (const std::string &driverPath, const std::string &driverSubPath, const std::string &captureDev) | |
virtual aditof::Status | dequeueInternalBuffer (struct v4l2_buffer &buf) override |
virtual aditof::Status | enqueueInternalBuffer (struct v4l2_buffer &buf) override |
virtual aditof::Status | getAvailableControls (std::vector< std::string > &controls) const override |
Gets the sensors's list of controls. More... | |
virtual aditof::Status | getAvailableModes (std::vector< uint8_t > &modes) override |
Return all modes that are supported by the sensor. More... | |
virtual aditof::Status | getControl (const std::string &control, std::string &value) const override |
Gets the value of a specific sensor control. More... | |
virtual aditof::Status | getDepthComputeParams (std::map< std::string, std::string > ¶ms) override |
Get ini parameters for Depth Compute library. More... | |
virtual aditof::Status | getDetails (aditof::SensorDetails &details) const override |
Get a structure that contains information about the instance of the sensor. More... | |
virtual aditof::Status | getDeviceFileDescriptor (int &fileDescriptor) override |
virtual aditof::Status | getFrame (uint16_t *buffer) override |
Request a frame from the sensor. More... | |
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 the other devices to communicate remotely with the embedded target. More... | |
aditof::Status | getIniParamsArrayForMode (int mode, std::string &iniStr) override |
Get ini parameters for Depth Compute library as string. More... | |
virtual aditof::Status | getInternalBuffer (uint8_t **buffer, uint32_t &buf_data_len, const struct v4l2_buffer &buf) override |
virtual aditof::Status | getModeDetails (const uint8_t &mode, aditof::DepthSensorModeDetails &details) override |
Returns details of specified mode. More... | |
virtual aditof::Status | getName (std::string &name) const override |
Get the name of the sensor. More... | |
virtual aditof::Status | initTargetDepthCompute (uint8_t *iniFile, uint16_t iniFileLength, uint8_t *calData, uint16_t calDataLength) override |
Get the name of the sensor. More... | |
virtual aditof::Status | open () override |
Open the communication channels with the hardware. More... | |
virtual aditof::Status | setControl (const std::string &control, const std::string &value) override |
Sets a specific sensor control. More... | |
virtual aditof::Status | setDepthComputeParams (const std::map< std::string, std::string > ¶ms) override |
Set ini parameters for Depth Compute library. More... | |
virtual aditof::Status | setHostConnectionType (std::string &connectionType) override |
Set the host connection type for target sdk. More... | |
virtual aditof::Status | setMode (const aditof::DepthSensorModeDetails &type) override |
Set the sensor frame mode to the given type. More... | |
virtual aditof::Status | setMode (const uint8_t &mode) override |
Set the sensor frame mode to the given type. More... | |
virtual aditof::Status | setSensorConfiguration (const std::string &sensorConf) override |
Set sensor configutation table. More... | |
virtual aditof::Status | start () override |
Start the streaming of data from the sensor. More... | |
virtual aditof::Status | stop () override |
Stop the sensor data stream. More... | |
virtual aditof::Status | waitForBuffer () override |
~Adsd3500Sensor () | |
![]() | |
virtual | ~DepthSensorInterface ()=default |
Destructor. More... | |
![]() | |
virtual | ~V4lBufferAccessInterface ()=default |
Private Attributes | |
bool | m_adsd3500Queried |
aditof::Adsd3500Status | m_adsd3500Status |
std::vector< aditof::DepthSensorModeDetails > | m_availableModes |
BufferProcessor * | m_bufferProcessor |
std::string | m_captureDev |
uint8_t | m_capturesPerFrame |
bool | m_ccbmEnabled |
std::vector< IniTableEntry > | m_ccbmINIContent |
bool | m_chipResetDone |
int | m_chipStatus |
std::unordered_map< std::string, std::string > | m_controls |
bool | m_depthComputeOnTarget |
std::string | m_driverPath |
std::string | m_driverSubPath |
bool | m_firstRun |
aditof::ConnectionType | m_hostConnectionType |
int | m_imagerStatus |
std::unique_ptr< ImplData > | m_implData |
std::vector< iniFileStruct > | m_iniFileStructList |
std::unordered_map< void *, aditof::SensorInterruptCallback > | m_interruptCallbackMap |
aditof::Adsd3500ModeSelector | m_modeSelector |
std::string | m_sensorConfiguration |
aditof::SensorDetails | m_sensorDetails |
unsigned int | m_sensorFps |
std::string | m_sensorName |
Definition at line 86 of file adsd3500_sensor.h.
Adsd3500Sensor::Adsd3500Sensor | ( | const std::string & | driverPath, |
const std::string & | driverSubPath, | ||
const std::string & | captureDev | ||
) |
Definition at line 128 of file adsd3500_sensor.cpp.
Adsd3500Sensor::~Adsd3500Sensor | ( | ) |
Definition at line 165 of file adsd3500_sensor.cpp.
|
overridevirtual |
Returns the chip status.
[out] | chipStatus | - chip status (error) value |
[out] | imagerStatus | - imager status (error) value |
Implements aditof::DepthSensorInterface.
Definition at line 1939 of file adsd3500_sensor.cpp.
|
overridevirtual |
Send a read command to adsd3500.
cmd | - the command to be sent | |
[out] | data | - the variable where the read data will be stored |
usDelay | - the number of microseconds to wait between the host command and the actual read |
Implements aditof::DepthSensorInterface.
Definition at line 997 of file adsd3500_sensor.cpp.
|
overridevirtual |
Reads a chunk of data from adsd3500. This will perform a burst read making it useful for reading chunks of data.
payload | - the location from where to take the data chunk and read it |
payload_len | - the number of bytes to read |
Implements aditof::DepthSensorInterface.
Definition at line 1203 of file adsd3500_sensor.cpp.
|
overridevirtual |
Send a read command to adsd3500. This will perform a burst read making it useful for reading chunks of data.
cmd | - the command to be sent | |
[out] | readback_data | - the location where the read data chunk will be stored |
payload_len | - the number of bytes to read |
Implements aditof::DepthSensorInterface.
Definition at line 1094 of file adsd3500_sensor.cpp.
|
overridevirtual |
Register a function to be called when a ADSD3500 interrupt occurs.
cb | - the function to be called whenever the interrupt occurs |
Implements aditof::DepthSensorInterface.
Definition at line 1885 of file adsd3500_sensor.cpp.
|
overridevirtual |
Reset adsd3500 chip.
Implements aditof::DepthSensorInterface.
Definition at line 1357 of file adsd3500_sensor.cpp.
|
overridevirtual |
Unregister a function registered with adsd3500_register_interrupt_callback.
cb | - the function to be unregistred |
Implements aditof::DepthSensorInterface.
Definition at line 1896 of file adsd3500_sensor.cpp.
|
overridevirtual |
Send a write command to adsd3500.
cmd | - the command to be sent |
data | - the data to be written |
usDelay | - the number of microseconds to wait between the host command and the actual write |
Implements aditof::DepthSensorInterface.
Definition at line 1054 of file adsd3500_sensor.cpp.
|
overridevirtual |
Send a chunk of data (payload) to adsd3500. This will perform a burst write making it useful for writing chunks of data.
payload | - the location from where to take the data chunk and write it |
payload_len | - the number of bytes to write |
Implements aditof::DepthSensorInterface.
Definition at line 1322 of file adsd3500_sensor.cpp.
|
overridevirtual |
Send a write command to adsd3500. This will perform a burst write making it useful for writing chunks of data.
cmd | - the command to be sent |
payload | - the location from where to take the data chunk and write it |
payload_len | - the number of bytes to write |
Implements aditof::DepthSensorInterface.
Definition at line 1249 of file adsd3500_sensor.cpp.
aditof::Status Adsd3500Sensor::adsd3500InterruptHandler | ( | int | signalValue | ) |
Definition at line 1904 of file adsd3500_sensor.cpp.
|
private |
Definition at line 1962 of file adsd3500_sensor.cpp.
|
private |
Definition at line 2126 of file adsd3500_sensor.cpp.
|
private |
|
overridevirtual |
Implements aditof::V4lBufferAccessInterface.
Definition at line 1630 of file adsd3500_sensor.cpp.
|
private |
Definition at line 1552 of file adsd3500_sensor.cpp.
|
overridevirtual |
Implements aditof::V4lBufferAccessInterface.
Definition at line 1642 of file adsd3500_sensor.cpp.
|
private |
Definition at line 1599 of file adsd3500_sensor.cpp.
|
overridevirtual |
Gets the sensors's list of controls.
[out] | controls |
Implements aditof::DepthSensorInterface.
Definition at line 796 of file adsd3500_sensor.cpp.
|
overridevirtual |
Return all modes that are supported by the sensor.
[out] | modes |
Implements aditof::DepthSensorInterface.
Definition at line 464 of file adsd3500_sensor.cpp.
|
overridevirtual |
Gets the value of a specific sensor control.
[in] | control | - Control name |
[out] | value | - Control value |
Implements aditof::DepthSensorInterface.
Definition at line 915 of file adsd3500_sensor.cpp.
|
private |
Definition at line 2058 of file adsd3500_sensor.cpp.
|
overridevirtual |
Get ini parameters for Depth Compute library.
[in] | params | - a dictionary of parameters |
Implements aditof::DepthSensorInterface.
Definition at line 1446 of file adsd3500_sensor.cpp.
|
overridevirtual |
Get a structure that contains information about the instance of the sensor.
[out] | details | - the variable where the sensor details should be stored |
Implements aditof::DepthSensorInterface.
Definition at line 969 of file adsd3500_sensor.cpp.
|
overridevirtual |
Implements aditof::V4lBufferAccessInterface.
Definition at line 1613 of file adsd3500_sensor.cpp.
|
overridevirtual |
Request a frame from the sensor.
buffer | - a valid location where the new frame should be stored. The size of the frame is known (cached) internally and gets updated each time setMode() is called. |
Implements aditof::DepthSensorInterface.
Definition at line 746 of file adsd3500_sensor.cpp.
|
overridevirtual |
Gets a handle to be used by other devices such as Storage, Temperature, etc. This handle will allow the other devices to communicate remotely with the embedded target.
[out] | handle | - the handle which is owned by this instance |
Implements aditof::DepthSensorInterface.
Definition at line 975 of file adsd3500_sensor.cpp.
|
overridevirtual |
Get ini parameters for Depth Compute library as string.
[in] | mode | - desired mode |
[out] | iniStr | - a string that contain ini params |
Implements aditof::DepthSensorInterface.
Definition at line 2137 of file adsd3500_sensor.cpp.
|
private |
Definition at line 2024 of file adsd3500_sensor.cpp.
|
overridevirtual |
Implements aditof::V4lBufferAccessInterface.
Definition at line 1636 of file adsd3500_sensor.cpp.
|
private |
Definition at line 1586 of file adsd3500_sensor.cpp.
|
overridevirtual |
Returns details of specified mode.
mode | ||
[out] | details |
Implements aditof::DepthSensorInterface.
Definition at line 477 of file adsd3500_sensor.cpp.
|
overridevirtual |
Get the name of the sensor.
[out] | name | - the string in which the name is stored |
Implements aditof::DepthSensorInterface.
Definition at line 980 of file adsd3500_sensor.cpp.
|
overridevirtual |
Get the name of the sensor.
[in] | iniFile | - iniFile content parsed as uint8_t* |
[in] | iniFileLength | - iniFile content length |
[in] | calData | - calibration data parsed as uint8_t* |
[in] | calDataLength | - calibration data content length |
Implements aditof::DepthSensorInterface.
Definition at line 1419 of file adsd3500_sensor.cpp.
|
private |
Definition at line 2080 of file adsd3500_sensor.cpp.
|
overridevirtual |
Open the communication channels with the hardware.
Implements aditof::DepthSensorInterface.
Definition at line 208 of file adsd3500_sensor.cpp.
|
private |
Definition at line 1652 of file adsd3500_sensor.cpp.
|
overridevirtual |
Sets a specific sensor control.
[in] | control | - Control name |
[in] | value | - Control value |
Implements aditof::DepthSensorInterface.
Definition at line 806 of file adsd3500_sensor.cpp.
|
overridevirtual |
Set ini parameters for Depth Compute library.
[in] | params | - a dictionary of parameters |
Implements aditof::DepthSensorInterface.
Definition at line 1487 of file adsd3500_sensor.cpp.
|
overridevirtual |
Set the host connection type for target sdk.
[in] | connectionType | - the string that sets the host type on the target |
Implements aditof::DepthSensorInterface.
Definition at line 987 of file adsd3500_sensor.cpp.
|
private |
Definition at line 2041 of file adsd3500_sensor.cpp.
|
overridevirtual |
Set the sensor frame mode to the given type.
type | - frame details structure containing the frame type |
Implements aditof::DepthSensorInterface.
Definition at line 541 of file adsd3500_sensor.cpp.
|
overridevirtual |
Set the sensor frame mode to the given type.
mode | - desired mode |
Implements aditof::DepthSensorInterface.
Definition at line 490 of file adsd3500_sensor.cpp.
|
overridevirtual |
Set sensor configutation table.
sensorConf | - Configuration table name string like e.g. standard, standardraw, custom and customraw |
Implements aditof::DepthSensorInterface.
Definition at line 1951 of file adsd3500_sensor.cpp.
|
overridevirtual |
Start the streaming of data from the sensor.
Implements aditof::DepthSensorInterface.
Definition at line 397 of file adsd3500_sensor.cpp.
|
overridevirtual |
Stop the sensor data stream.
Implements aditof::DepthSensorInterface.
Definition at line 439 of file adsd3500_sensor.cpp.
|
overridevirtual |
Implements aditof::V4lBufferAccessInterface.
Definition at line 1625 of file adsd3500_sensor.cpp.
|
private |
Definition at line 1524 of file adsd3500_sensor.cpp.
|
private |
Definition at line 1647 of file adsd3500_sensor.cpp.
|
private |
Definition at line 213 of file adsd3500_sensor.h.
|
private |
Definition at line 222 of file adsd3500_sensor.h.
|
private |
Definition at line 216 of file adsd3500_sensor.h.
|
private |
Definition at line 218 of file adsd3500_sensor.h.
|
private |
Definition at line 207 of file adsd3500_sensor.h.
|
private |
Definition at line 210 of file adsd3500_sensor.h.
|
private |
Definition at line 227 of file adsd3500_sensor.h.
|
private |
Definition at line 217 of file adsd3500_sensor.h.
|
private |
Definition at line 223 of file adsd3500_sensor.h.
|
private |
Definition at line 220 of file adsd3500_sensor.h.
|
private |
Definition at line 208 of file adsd3500_sensor.h.
|
private |
Definition at line 219 of file adsd3500_sensor.h.
|
private |
Definition at line 205 of file adsd3500_sensor.h.
|
private |
Definition at line 206 of file adsd3500_sensor.h.
|
private |
Definition at line 211 of file adsd3500_sensor.h.
|
private |
Definition at line 204 of file adsd3500_sensor.h.
|
private |
Definition at line 221 of file adsd3500_sensor.h.
|
private |
Definition at line 209 of file adsd3500_sensor.h.
|
private |
Definition at line 224 of file adsd3500_sensor.h.
|
private |
Definition at line 215 of file adsd3500_sensor.h.
|
private |
Definition at line 225 of file adsd3500_sensor.h.
|
private |
Definition at line 226 of file adsd3500_sensor.h.
|
private |
Definition at line 203 of file adsd3500_sensor.h.
|
private |
Definition at line 212 of file adsd3500_sensor.h.
|
private |
Definition at line 201 of file adsd3500_sensor.h.