network_depth_sensor.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 NETWORK_DEPTH_SENSOR_H
33 #define NETWORK_DEPTH_SENSOR_H
34 
36 
37 #include <memory>
38 #include <thread>
39 #include <unordered_map>
40 
42  public:
45 
46  public: // implements DepthSensorInterface
47  virtual aditof::Status open() override;
48  virtual aditof::Status start() override;
49  virtual aditof::Status stop() override;
50  virtual aditof::Status
51  getAvailableModes(std::vector<uint8_t> &modes) override;
52  virtual aditof::Status
53  getModeDetails(const uint8_t &mode,
54  aditof::DepthSensorModeDetails &details) override;
55  virtual aditof::Status
57  virtual aditof::Status setMode(const uint8_t &mode) override;
58  virtual aditof::Status getFrame(uint16_t *buffer) override;
59  virtual aditof::Status
60  getAvailableControls(std::vector<std::string> &controls) const override;
61  virtual aditof::Status setControl(const std::string &control,
62  const std::string &value) override;
63  virtual aditof::Status getControl(const std::string &control,
64  std::string &value) const override;
65  virtual aditof::Status
66  getDetails(aditof::SensorDetails &details) const override;
67  virtual aditof::Status getHandle(void **handle) override;
68  virtual aditof::Status getName(std::string &name) const override;
69  virtual aditof::Status
70  setHostConnectionType(std::string &connectionType) override;
71 
72  virtual aditof::Status adsd3500_read_cmd(uint16_t cmd, uint16_t *data,
73  unsigned int usDelay = 0) override;
74  virtual aditof::Status
75  adsd3500_write_cmd(uint16_t cmd, uint16_t data,
76  unsigned int usDelay = 0) override;
77  virtual aditof::Status
78  adsd3500_read_payload_cmd(uint32_t cmd, uint8_t *readback_data,
79  uint16_t payload_len) override;
80  virtual aditof::Status adsd3500_read_payload(uint8_t *payload,
81  uint16_t payload_len) override;
82  virtual aditof::Status
83  adsd3500_write_payload_cmd(uint32_t cmd, uint8_t *payload,
84  uint16_t payload_len) override;
85  virtual aditof::Status
86  adsd3500_write_payload(uint8_t *payload, uint16_t payload_len) override;
87  virtual aditof::Status adsd3500_reset() override;
89  aditof::SensorInterruptCallback &cb) override;
91  aditof::SensorInterruptCallback &cb) override;
92  virtual aditof::Status adsd3500_get_status(int &chipStatus,
93  int &imagerStatus) override;
94  virtual aditof::Status
95  initTargetDepthCompute(uint8_t *iniFile, uint16_t iniFileLength,
96  uint8_t *calData, uint16_t calDataLength) override;
97  virtual aditof::Status
98  getDepthComputeParams(std::map<std::string, std::string> &params) override;
99 
101  const std::map<std::string, std::string> &params) override;
103  setSensorConfiguration(const std::string &sensorConf) override;
104 
106  std::string &iniStr) override;
107 
108  private:
109  void checkForServerUpdates();
110 
111  private:
112  struct ImplData;
115  std::unique_ptr<ImplData> m_implData;
117  static int m_sensorCounter;
118  std::unordered_map<void *, aditof::SensorInterruptCallback>
122 
123  static int frame_size;
124 };
125 
126 #endif // NETWORK_DEPTH_SENSOR_H
NetworkDepthSensor::adsd3500_write_payload_cmd
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...
Definition: network_depth_sensor.cpp:1040
name
GLuint const GLchar * name
Definition: glcorearb.h:3055
NetworkDepthSensor::adsd3500_write_payload
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...
Definition: network_depth_sensor.cpp:1082
NetworkDepthSensor::getDepthComputeParams
virtual aditof::Status getDepthComputeParams(std::map< std::string, std::string > &params) override
Get ini parameters for Depth Compute library.
Definition: network_depth_sensor.cpp:157
aditof::SensorDetails
Provides details about the device.
Definition: sensor_definitions.h:50
NetworkDepthSensor::m_activityCheckThread
std::thread m_activityCheckThread
Definition: network_depth_sensor.h:121
NetworkDepthSensor::setMode
virtual aditof::Status setMode(const aditof::DepthSensorModeDetails &type) override
Set the sensor frame mode to the given type.
Definition: network_depth_sensor.cpp:581
NetworkDepthSensor::getAvailableModes
virtual aditof::Status getAvailableModes(std::vector< uint8_t > &modes) override
Return all modes that are supported by the sensor.
Definition: network_depth_sensor.cpp:426
mode
GLenum mode
Definition: glcorearb.h:2764
NetworkDepthSensor::checkForServerUpdates
void checkForServerUpdates()
Definition: network_depth_sensor.cpp:1252
NetworkDepthSensor::getHandle
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...
Definition: network_depth_sensor.cpp:836
string
GLsizei const GLchar *const * string
Definition: glcorearb.h:3083
NetworkDepthSensor::adsd3500_get_status
virtual aditof::Status adsd3500_get_status(int &chipStatus, int &imagerStatus) override
Returns the chip status.
Definition: network_depth_sensor.cpp:1170
NetworkDepthSensor::initTargetDepthCompute
virtual aditof::Status initTargetDepthCompute(uint8_t *iniFile, uint16_t iniFileLength, uint8_t *calData, uint16_t calDataLength) override
Get the name of the sensor.
Definition: network_depth_sensor.cpp:1209
NetworkDepthSensor::setSensorConfiguration
aditof::Status setSensorConfiguration(const std::string &sensorConf) override
Set sensor configutation table.
Definition: network_depth_sensor.cpp:1283
NetworkDepthSensor::getName
virtual aditof::Status getName(std::string &name) const override
Get the name of the sensor.
Definition: network_depth_sensor.cpp:848
NetworkDepthSensor::adsd3500_unregister_interrupt_callback
virtual aditof::Status adsd3500_unregister_interrupt_callback(aditof::SensorInterruptCallback &cb) override
Unregister a function registered with adsd3500_register_interrupt_callback.
Definition: network_depth_sensor.cpp:1162
NetworkDepthSensor::adsd3500_read_cmd
virtual aditof::Status adsd3500_read_cmd(uint16_t cmd, uint16_t *data, unsigned int usDelay=0) override
Send a read command to adsd3500.
Definition: network_depth_sensor.cpp:859
NetworkDepthSensor::m_sensorCounter
static int m_sensorCounter
Definition: network_depth_sensor.h:117
NetworkDepthSensor::getFrame
virtual aditof::Status getFrame(uint16_t *buffer) override
Request a frame from the sensor.
Definition: network_depth_sensor.cpp:649
NetworkDepthSensor::frame_size
static int frame_size
Definition: network_depth_sensor.h:123
NetworkDepthSensor::setHostConnectionType
virtual aditof::Status setHostConnectionType(std::string &connectionType) override
Set the host connection type for target sdk.
Definition: network_depth_sensor.cpp:854
NetworkDepthSensor::adsd3500_write_cmd
virtual aditof::Status adsd3500_write_cmd(uint16_t cmd, uint16_t data, unsigned int usDelay=0) override
Send a write command to adsd3500.
Definition: network_depth_sensor.cpp:905
NetworkDepthSensor::getDetails
virtual aditof::Status getDetails(aditof::SensorDetails &details) const override
Get a structure that contains information about the instance of the sensor.
Definition: network_depth_sensor.cpp:831
NetworkDepthSensor::ImplData
Definition: network_depth_sensor.cpp:49
NetworkDepthSensor::start
virtual aditof::Status start() override
Start the streaming of data from the sensor.
Definition: network_depth_sensor.cpp:323
NetworkDepthSensor::adsd3500_register_interrupt_callback
virtual aditof::Status adsd3500_register_interrupt_callback(aditof::SensorInterruptCallback &cb) override
Register a function to be called when a ADSD3500 interrupt occurs.
Definition: network_depth_sensor.cpp:1156
NetworkDepthSensor::NetworkDepthSensor
NetworkDepthSensor(const std::string &name, const std::string &ip)
Definition: network_depth_sensor.cpp:60
params
GLenum const GLfloat * params
Definition: glcorearb.h:2770
NetworkDepthSensor::stop
virtual aditof::Status stop() override
Stop the sensor data stream.
Definition: network_depth_sensor.cpp:385
buffer
Definition: buffer_processor.h:43
NetworkDepthSensor::m_stopServerCheck
bool m_stopServerCheck
Definition: network_depth_sensor.h:120
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
NetworkDepthSensor::adsd3500_read_payload
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...
Definition: network_depth_sensor.cpp:996
NetworkDepthSensor::getControl
virtual aditof::Status getControl(const std::string &control, std::string &value) const override
Gets the value of a specific sensor control.
Definition: network_depth_sensor.cpp:789
type
GLenum type
Definition: glcorearb.h:2695
NetworkDepthSensor::setDepthComputeParams
virtual aditof::Status setDepthComputeParams(const std::map< std::string, std::string > &params) override
Set ini parameters for Depth Compute library.
Definition: network_depth_sensor.cpp:219
NetworkDepthSensor::getModeDetails
virtual aditof::Status getModeDetails(const uint8_t &mode, aditof::DepthSensorModeDetails &details) override
Returns details of specified mode.
Definition: network_depth_sensor.cpp:472
NetworkDepthSensor::adsd3500_reset
virtual aditof::Status adsd3500_reset() override
Reset adsd3500 chip.
Definition: network_depth_sensor.cpp:1121
NetworkDepthSensor::m_sensorDetails
aditof::SensorDetails m_sensorDetails
Definition: network_depth_sensor.h:114
aditof::DepthSensorModeDetails
Describes the type of entire frame that a depth sensor can capture and transmit.
Definition: sensor_definitions.h:120
NetworkDepthSensor::m_implData
std::unique_ptr< ImplData > m_implData
Definition: network_depth_sensor.h:115
NetworkDepthSensor::~NetworkDepthSensor
~NetworkDepthSensor()
Definition: network_depth_sensor.cpp:124
data
GLint GLenum GLsizei GLsizei GLsizei GLint GLsizei const GLvoid * data
Definition: glcorearb.h:2879
NetworkDepthSensor::open
virtual aditof::Status open() override
Open the communication channels with the hardware.
Definition: network_depth_sensor.cpp:275
NetworkDepthSensor::adsd3500_read_payload_cmd
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...
Definition: network_depth_sensor.cpp:948
value
GLsizei const GLfloat * value
Definition: glcorearb.h:3093
NetworkDepthSensor::getAvailableControls
virtual aditof::Status getAvailableControls(std::vector< std::string > &controls) const override
Gets the sensors's list of controls.
Definition: network_depth_sensor.cpp:704
NetworkDepthSensor::m_interruptCallbackMap
std::unordered_map< void *, aditof::SensorInterruptCallback > m_interruptCallbackMap
Definition: network_depth_sensor.h:119
NetworkDepthSensor
Definition: network_depth_sensor.h:41
NetworkDepthSensor::setControl
virtual aditof::Status setControl(const std::string &control, const std::string &value) override
Sets a specific sensor control.
Definition: network_depth_sensor.cpp:751
NetworkDepthSensor::getIniParamsArrayForMode
aditof::Status getIniParamsArrayForMode(int mode, std::string &iniStr) override
Get ini parameters for Depth Compute library as string.
Definition: network_depth_sensor.cpp:1320
NetworkDepthSensor::m_sensorName
std::string m_sensorName
Definition: network_depth_sensor.h:112
depth_sensor_interface.h
NetworkDepthSensor::m_sensorIndex
int m_sensorIndex
Definition: network_depth_sensor.h:116
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:57