depth_sensor_interface.h
Go to the documentation of this file.
1 /*
2  * BSD 3-Clause License
3  *
4  * Copyright (c) 2019, Analog Devices, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions are met:
9  *
10  * 1. Redistributions of source code must retain the above copyright notice, this
11  * list of conditions and the following disclaimer.
12  *
13  * 2. Redistributions in binary form must reproduce the above copyright notice,
14  * this list of conditions and the following disclaimer in the documentation
15  * and/or other materials provided with the distribution.
16  *
17  * 3. Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived from
19  * this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
22  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
23  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
24  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
25  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
26  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
27  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
29  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
30  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
31  */
32 #ifndef DEPTH_SENSOR_INTERFACE_H
33 #define DEPTH_SENSOR_INTERFACE_H
34 
38 
39 #include <cstddef>
40 #include <functional>
41 #include <map>
42 #include <string>
43 #include <vector>
44 
45 namespace aditof {
46 
51 
58  public:
62  virtual ~DepthSensorInterface() = default;
63 
68  virtual aditof::Status open() = 0;
69 
74  virtual aditof::Status start() = 0;
75 
80  virtual aditof::Status stop() = 0;
81 
87  virtual aditof::Status getAvailableModes(std::vector<uint8_t> &modes) = 0;
88 
95  virtual aditof::Status
96  getModeDetails(const uint8_t &mode,
97  aditof::DepthSensorModeDetails &details) = 0;
98 
104  virtual aditof::Status setMode(const uint8_t &mode) = 0;
105 
111  virtual aditof::Status
113 
121  virtual aditof::Status getFrame(uint16_t *buffer) = 0;
122 
131  virtual aditof::Status adsd3500_read_cmd(uint16_t cmd, uint16_t *data,
132  unsigned int usDelay = 0) = 0;
133 
142  virtual aditof::Status adsd3500_write_cmd(uint16_t cmd, uint16_t data,
143  unsigned int usDelay = 0) = 0;
144 
153  virtual aditof::Status adsd3500_read_payload_cmd(uint32_t cmd,
154  uint8_t *readback_data,
155  uint16_t payload_len) = 0;
156 
164  virtual aditof::Status adsd3500_read_payload(uint8_t *payload,
165  uint16_t payload_len) = 0;
166 
175  virtual aditof::Status adsd3500_write_payload_cmd(uint32_t cmd,
176  uint8_t *payload,
177  uint16_t payload_len) = 0;
178 
186  virtual aditof::Status adsd3500_write_payload(uint8_t *payload,
187  uint16_t payload_len) = 0;
188 
193  virtual aditof::Status adsd3500_reset() = 0;
194 
200  virtual aditof::Status
202 
208  virtual aditof::Status
210 
217  virtual aditof::Status adsd3500_get_status(int &chipStatus,
218  int &imagerStatus) = 0;
219 
225  virtual Status
226  getAvailableControls(std::vector<std::string> &controls) const = 0;
227 
234  virtual Status setControl(const std::string &control,
235  const std::string &value) = 0;
236 
243  virtual Status getControl(const std::string &control,
244  std::string &value) const = 0;
245 
253  virtual aditof::Status getDetails(aditof::SensorDetails &details) const = 0;
254 
262  virtual aditof::Status getHandle(void **handle) = 0;
263 
269  virtual aditof::Status getName(std::string &name) const = 0;
270 
276  virtual aditof::Status
277  setHostConnectionType(std::string &connectionType) = 0;
278 
287  virtual aditof::Status initTargetDepthCompute(uint8_t *iniFile,
288  uint16_t iniFileLength,
289  uint8_t *calData,
290  uint16_t calDataLength) = 0;
291 
297  virtual aditof::Status
298  getDepthComputeParams(std::map<std::string, std::string> &params) = 0;
299 
305  virtual aditof::Status
306  setDepthComputeParams(const std::map<std::string, std::string> &params) = 0;
307 
314  virtual aditof::Status
315  setSensorConfiguration(const std::string &sensorConf) = 0;
316 
324  std::string &iniStr) = 0;
325 };
326 
327 } // namespace aditof
328 
329 #endif // DEPTH_SENSOR_INTERFACE_H
aditof::DepthSensorInterface::adsd3500_get_status
virtual aditof::Status adsd3500_get_status(int &chipStatus, int &imagerStatus)=0
Returns the chip status.
aditof::DepthSensorInterface::getFrame
virtual aditof::Status getFrame(uint16_t *buffer)=0
Request a frame from the sensor.
name
GLuint const GLchar * name
Definition: glcorearb.h:3055
aditof::DepthSensorInterface::adsd3500_reset
virtual aditof::Status adsd3500_reset()=0
Reset adsd3500 chip.
aditof::DepthSensorInterface::adsd3500_read_cmd
virtual aditof::Status adsd3500_read_cmd(uint16_t cmd, uint16_t *data, unsigned int usDelay=0)=0
Send a read command to adsd3500.
aditof::SensorDetails
Provides details about the device.
Definition: sensor_definitions.h:50
mode
GLenum mode
Definition: glcorearb.h:2764
aditof::DepthSensorInterface::getDepthComputeParams
virtual aditof::Status getDepthComputeParams(std::map< std::string, std::string > &params)=0
Get ini parameters for Depth Compute library.
aditof::DepthSensorInterface::setMode
virtual aditof::Status setMode(const uint8_t &mode)=0
Set the sensor frame mode to the given type.
aditof::DepthSensorInterface::getName
virtual aditof::Status getName(std::string &name) const =0
Get the name of the sensor.
aditof::DepthSensorInterface::adsd3500_write_cmd
virtual aditof::Status adsd3500_write_cmd(uint16_t cmd, uint16_t data, unsigned int usDelay=0)=0
Send a write command to adsd3500.
string
GLsizei const GLchar *const * string
Definition: glcorearb.h:3083
aditof::DepthSensorInterface::stop
virtual aditof::Status stop()=0
Stop the sensor data stream.
aditof::Adsd3500Status
Adsd3500Status
Status of the ADSD3500 sensor.
Definition: status_definitions.h:61
aditof::DepthSensorInterface::getDetails
virtual aditof::Status getDetails(aditof::SensorDetails &details) const =0
Get a structure that contains information about the instance of the sensor.
aditof::DepthSensorInterface::adsd3500_read_payload_cmd
virtual aditof::Status adsd3500_read_payload_cmd(uint32_t cmd, uint8_t *readback_data, uint16_t payload_len)=0
Send a read command to adsd3500. This will perform a burst read making it useful for reading chunks o...
aditof::DepthSensorInterface::adsd3500_read_payload
virtual aditof::Status adsd3500_read_payload(uint8_t *payload, uint16_t payload_len)=0
Reads a chunk of data from adsd3500. This will perform a burst read making it useful for reading chun...
aditof::DepthSensorInterface::setDepthComputeParams
virtual aditof::Status setDepthComputeParams(const std::map< std::string, std::string > &params)=0
Set ini parameters for Depth Compute library.
aditof::DepthSensorInterface::setHostConnectionType
virtual aditof::Status setHostConnectionType(std::string &connectionType)=0
Set the host connection type for target sdk.
aditof::DepthSensorInterface::getAvailableControls
virtual Status getAvailableControls(std::vector< std::string > &controls) const =0
Gets the sensors's list of controls.
aditof::DepthSensorInterface::setSensorConfiguration
virtual aditof::Status setSensorConfiguration(const std::string &sensorConf)=0
Set sensor configutation table.
aditof
Namespace aditof.
Definition: adsd_errs.h:40
aditof::DepthSensorInterface::start
virtual aditof::Status start()=0
Start the streaming of data from the sensor.
aditof::DepthSensorInterface::adsd3500_unregister_interrupt_callback
virtual aditof::Status adsd3500_unregister_interrupt_callback(SensorInterruptCallback &cb)=0
Unregister a function registered with adsd3500_register_interrupt_callback.
aditof::DepthSensorInterface::adsd3500_register_interrupt_callback
virtual aditof::Status adsd3500_register_interrupt_callback(SensorInterruptCallback &cb)=0
Register a function to be called when a ADSD3500 interrupt occurs.
frame_definitions.h
aditof::DepthSensorInterface::~DepthSensorInterface
virtual ~DepthSensorInterface()=default
Destructor.
aditof::DepthSensorInterface::getModeDetails
virtual aditof::Status getModeDetails(const uint8_t &mode, aditof::DepthSensorModeDetails &details)=0
Returns details of specified mode.
params
GLenum const GLfloat * params
Definition: glcorearb.h:2770
buffer
Definition: buffer_processor.h:43
aditof::DepthSensorInterface::getHandle
virtual aditof::Status getHandle(void **handle)=0
Gets a handle to be used by other devices such as Storage, Temperature, etc. This handle will allow t...
aditof::DepthSensorInterface::open
virtual aditof::Status open()=0
Open the communication channels with the hardware.
void
typedef void(APIENTRY *GLDEBUGPROCARB)(GLenum source
aditof::DepthSensorInterface::initTargetDepthCompute
virtual aditof::Status initTargetDepthCompute(uint8_t *iniFile, uint16_t iniFileLength, uint8_t *calData, uint16_t calDataLength)=0
Get the name of the sensor.
aditof::Status
Status
Status of any operation that the TOF sdk performs.
Definition: status_definitions.h:48
aditof::DepthSensorInterface
Provides access to the low level functionality of the camera sensor. This includes sensor configurati...
Definition: depth_sensor_interface.h:57
type
GLenum type
Definition: glcorearb.h:2695
aditof::DepthSensorInterface::adsd3500_write_payload
virtual aditof::Status adsd3500_write_payload(uint8_t *payload, uint16_t payload_len)=0
Send a chunk of data (payload) to adsd3500. This will perform a burst write making it useful for writ...
aditof::DepthSensorModeDetails
Describes the type of entire frame that a depth sensor can capture and transmit.
Definition: sensor_definitions.h:120
aditof::DepthSensorInterface::setControl
virtual Status setControl(const std::string &control, const std::string &value)=0
Sets a specific sensor control.
aditof::DepthSensorInterface::getControl
virtual Status getControl(const std::string &control, std::string &value) const =0
Gets the value of a specific sensor control.
aditof::DepthSensorInterface::adsd3500_write_payload_cmd
virtual aditof::Status adsd3500_write_payload_cmd(uint32_t cmd, uint8_t *payload, uint16_t payload_len)=0
Send a write command to adsd3500. This will perform a burst write making it useful for writing chunks...
sensor_definitions.h
data
GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const GLvoid * data
Definition: glcorearb.h:2879
status_definitions.h
value
GLsizei const GLfloat * value
Definition: glcorearb.h:3093
aditof::DepthSensorInterface::getAvailableModes
virtual aditof::Status getAvailableModes(std::vector< uint8_t > &modes)=0
Return all modes that are supported by the sensor.
aditof::DepthSensorInterface::getIniParamsArrayForMode
virtual aditof::Status getIniParamsArrayForMode(int mode, std::string &iniStr)=0
Get ini parameters for Depth Compute library as string.
aditof::SensorInterruptCallback
std::function< void(Adsd3500Status)> SensorInterruptCallback
Callback for sensor interrupts.
Definition: depth_sensor_interface.h:50


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