network_depth_sensor.cpp
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 #include "network_depth_sensor.h"
34 
35 #ifdef USE_GLOG
36 #include <glog/logging.h>
37 #else
38 #include <aditof/log.h>
39 #endif
40 #include <chrono>
41 #include <unordered_map>
42 
45  float gain;
46  float offset;
47  uint16_t *cache;
48 };
53  std::unordered_map<std::string, CalibrationData> calibration_cache;
54  bool opened;
56 };
57 
59 
61  const std::string &ip)
62  : m_implData(new NetworkDepthSensor::ImplData), m_stopServerCheck(false) {
63 
64  extern std::vector<std::string> m_connectionList;
65  m_sensorIndex = -1;
66  for (int i = 0; i < m_connectionList.size(); i++) {
67  if (m_connectionList.at(i) == ip) {
68  m_sensorIndex = i;
69  }
70  }
71 
72  if (m_sensorIndex == -1) {
73  LOG(ERROR) << "No sensors available at: " << ip;
74  return;
75  }
76 
77  m_implData->cb = [this]() {
78  Network *net = m_implData->handle.net;
79 
80  if (!net->isServer_Connected()) {
81  LOG(WARNING) << "Not connected to server";
82  return;
83  }
84 
85  net->send_buff[m_sensorIndex].set_func_name("GetInterrupts");
86  net->send_buff[m_sensorIndex].set_expect_reply(true);
87 
88  if (net->SendCommand() != 0) {
89  LOG(WARNING) << "Send Command Failed";
90  return;
91  }
92 
93  if (net->recv_server_data() != 0) {
94  LOG(WARNING) << "Receive Data Failed";
95  return;
96  }
97 
98  if (net->recv_buff[m_sensorIndex].server_status() !=
99  payload::ServerStatus::REQUEST_ACCEPTED) {
100  LOG(WARNING) << "API execution on Target Failed";
101  return;
102  }
103 
104  for (int32_t i = 0;
105  i < net->recv_buff[m_sensorIndex].int32_payload_size(); ++i) {
106  for (auto m_interruptCallback : m_interruptCallbackMap) {
107  m_interruptCallback.second(
109  .int32_payload(i));
110  }
111  }
112  };
113 
114  Network *net = new Network(m_sensorIndex);
115  m_implData->handle.net = net;
116  m_implData->handle.net->registerInterruptCallback(m_implData->cb);
117  m_implData->ip = ip;
118  m_implData->opened = false;
120  m_sensorDetails.id = ip;
121  m_sensorName = name;
122 }
123 
125  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
126 
127  // If channel communication has been opened, let the server know we're hanging up
128  if (m_implData->opened) {
129  if (!m_implData->handle.net->isServer_Connected()) {
130  LOG(WARNING) << "Not connected to server";
131  }
132 
133  m_implData->handle.net->send_buff[m_sensorIndex].set_func_name(
134  "HangUp");
135  m_implData->handle.net->send_buff[m_sensorIndex].set_expect_reply(
136  false);
137 
138  if (m_implData->handle.net->SendCommand() != 0) {
139  LOG(WARNING) << "Send Command Failed";
140  }
141 
142  if (!m_stopServerCheck) {
143  m_stopServerCheck = true;
144  m_activityCheckThread.join();
145  }
146  }
147 
148  delete m_implData->handle.net;
149 
150  for (auto it = m_implData->calibration_cache.begin();
151  it != m_implData->calibration_cache.begin(); ++it) {
152  delete[] it->second.cache;
153  it->second.cache = nullptr;
154  }
155 }
156 
158  std::map<std::string, std::string> &params) {
159  using namespace aditof;
160  Network *net = m_implData->handle.net;
161  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
162 
163  if (!net->isServer_Connected()) {
164  LOG(WARNING) << "Not connected to server";
165  return Status::UNREACHABLE;
166  }
167 
168  net->send_buff[m_sensorIndex].set_func_name("GetDepthComputeParam");
169  net->send_buff[m_sensorIndex].set_expect_reply(true);
170 
171  if (net->SendCommand() != 0) {
172  LOG(WARNING) << "Send Command Failed";
174  }
175 
176  if (net->recv_server_data() != 0) {
177  LOG(WARNING) << "Receive Data Failed";
178  return Status::GENERIC_ERROR;
179  }
180 
181  if (net->recv_buff[m_sensorIndex].server_status() !=
182  payload::ServerStatus::REQUEST_ACCEPTED) {
183  LOG(WARNING) << "API execution on Target Failed";
184  return Status::GENERIC_ERROR;
185  }
186 
187  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
188 
189  if (status == Status::OK) {
190  params["abThreshMin"] =
191  (net->recv_buff[m_sensorIndex].strings_payload(0));
192  params["abSumThresh"] =
193  (net->recv_buff[m_sensorIndex].strings_payload(1));
194  params["confThresh"] =
195  (net->recv_buff[m_sensorIndex].strings_payload(2));
196  params["radialThreshMin"] =
197  (net->recv_buff[m_sensorIndex].strings_payload(3));
198  params["radialThreshMax"] =
199  (net->recv_buff[m_sensorIndex].strings_payload(4));
200  params["jblfApplyFlag"] =
201  (net->recv_buff[m_sensorIndex].strings_payload(5));
202  params["jblfWindowSize"] =
203  (net->recv_buff[m_sensorIndex].strings_payload(6));
204  params["jblfGaussianSigma"] =
205  (net->recv_buff[m_sensorIndex].strings_payload(7));
206  params["jblfExponentialTerm"] =
207  (net->recv_buff[m_sensorIndex].strings_payload(8));
208  params["jblfMaxEdge"] =
209  (net->recv_buff[m_sensorIndex].strings_payload(9));
210  params["jblfABThreshold"] =
211  (net->recv_buff[m_sensorIndex].strings_payload(10));
212  params["headerSize"] =
213  (net->recv_buff[m_sensorIndex].strings_payload(11));
214  }
215 
216  return status;
217 }
218 
220  const std::map<std::string, std::string> &params) {
221  using namespace aditof;
222  Network *net = m_implData->handle.net;
223  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
224 
225  if (!net->isServer_Connected()) {
226  LOG(WARNING) << "Not connected to server";
227  return Status::UNREACHABLE;
228  }
229 
230  net->send_buff[m_sensorIndex].set_func_name("SetDepthComputeParam");
231  net->send_buff[m_sensorIndex].set_expect_reply(true);
232  net->send_buff[m_sensorIndex].add_func_strings_param(
233  params.at("abThreshMin"));
234  net->send_buff[m_sensorIndex].add_func_strings_param(
235  params.at("abSumThresh"));
236  net->send_buff[m_sensorIndex].add_func_strings_param(
237  params.at("confThresh"));
238  net->send_buff[m_sensorIndex].add_func_strings_param(
239  params.at("radialThreshMin"));
240  net->send_buff[m_sensorIndex].add_func_strings_param(
241  params.at("radialThreshMax"));
242  net->send_buff[m_sensorIndex].add_func_strings_param(
243  params.at("jblfApplyFlag"));
244  net->send_buff[m_sensorIndex].add_func_strings_param(
245  params.at("jblfWindowSize"));
246  net->send_buff[m_sensorIndex].add_func_strings_param(
247  params.at("jblfGaussianSigma"));
248  net->send_buff[m_sensorIndex].add_func_strings_param(
249  params.at("jblfExponentialTerm"));
250  net->send_buff[m_sensorIndex].add_func_strings_param(
251  params.at("jblfMaxEdge"));
252  net->send_buff[m_sensorIndex].add_func_strings_param(
253  params.at("jblfABThreshold"));
254 
255  if (net->SendCommand() != 0) {
256  LOG(WARNING) << "Send Command Failed";
258  }
259 
260  if (net->recv_server_data() != 0) {
261  LOG(WARNING) << "Receive Data Failed";
262  return Status::GENERIC_ERROR;
263  }
264 
265  if (net->recv_buff[m_sensorIndex].server_status() !=
266  payload::ServerStatus::REQUEST_ACCEPTED) {
267  LOG(WARNING) << "API execution on Target Failed";
268  return Status::GENERIC_ERROR;
269  }
270 
271  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
272  return status;
273 }
274 
276  using namespace aditof;
277 
278  Network *net = m_implData->handle.net;
279  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
280 
281  if (net->ServerConnect(m_implData->ip) != 0) {
282  LOG(WARNING) << "Server Connect Failed";
283  return Status::UNREACHABLE;
284  }
285 
286  if (!net->isServer_Connected()) {
287  LOG(WARNING) << "Not connected to server";
288  return Status::UNREACHABLE;
289  }
290 
291  net->send_buff[m_sensorIndex].set_func_name("Open");
292  net->send_buff[m_sensorIndex].set_expect_reply(true);
293 
294  if (net->SendCommand() != 0) {
295  LOG(WARNING) << "Send Command Failed";
297  }
298 
299  if (net->recv_server_data() != 0) {
300  LOG(WARNING) << "Receive Data Failed";
301  return Status::GENERIC_ERROR;
302  }
303 
304  if (net->recv_buff[m_sensorIndex].server_status() !=
305  payload::ServerStatus::REQUEST_ACCEPTED) {
306  LOG(WARNING) << "API execution on Target Failed";
307  return Status::GENERIC_ERROR;
308  }
309 
310  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
311 
312  if (status == Status::OK) {
313  m_implData->opened = true;
314 
315  // Create a new thread that periodically checks for inactivity on client-network then goes back to sleep
317  std::thread(&NetworkDepthSensor::checkForServerUpdates, this);
318  }
319 
320  return status;
321 }
322 
324  using namespace aditof;
325 
326  Network *net = m_implData->handle.net;
327  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
328 
329  if (!net->isServer_Connected()) {
330  LOG(WARNING) << "Not connected to server";
331  return Status::UNREACHABLE;
332  }
333 
334 #ifdef RECV_ASYNC
335  LOG(INFO) << "Configuring to receive frame in async mode";
336  std::string reply_async = "send_async";
337  net->send_buff[m_sensorIndex].set_func_name("RecvAsync");
338  net->send_buff[m_sensorIndex].set_expect_reply(true);
339 
340  if (net->SendCommand() != 0) {
341  LOG(WARNING) << "Send Command Failed";
343  }
344 
345  if (net->recv_server_data() != 0) {
346  LOG(WARNING) << "Receive Data Failed";
347  return Status::GENERIC_ERROR;
348  }
349 
350  if (net->recv_buff[m_sensorIndex].message().c_str() != reply_async) {
351  LOG(WARNING) << "Target is not build to send in async mode";
352  return Status::GENERIC_ERROR;
353  }
354 
355 #endif
356 
357  // Start the sensor
358 
359  net->send_buff[m_sensorIndex].set_func_name("Start");
360  net->send_buff[m_sensorIndex].set_expect_reply(true);
361 
362  if (net->SendCommand() != 0) {
363  LOG(WARNING) << "Send Command Failed";
365  }
366 
367  if (net->recv_server_data() != 0) {
368  LOG(WARNING) << "Receive Data Failed";
369  return Status::GENERIC_ERROR;
370  }
371 
372  if (net->recv_buff[m_sensorIndex].server_status() !=
373  payload::ServerStatus::REQUEST_ACCEPTED) {
374  LOG(WARNING) << "API execution on Target Failed";
375  return Status::GENERIC_ERROR;
376  }
377 
378  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
379 
381 
382  return status;
383 }
384 
386  using namespace aditof;
387 
388  Network *net = m_implData->handle.net;
389  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
390 
391  LOG(INFO) << "Stopping device";
392 
393  if (!net->isServer_Connected()) {
394  LOG(WARNING) << "Not connected to server";
395  return Status::UNREACHABLE;
396  }
397 
398  net->send_buff[m_sensorIndex].set_func_name("Stop");
399  net->send_buff[m_sensorIndex].set_expect_reply(true);
400 
401  if (net->SendCommand() != 0) {
402  LOG(WARNING) << "Send Command Failed";
404  }
405 
406  if (net->recv_server_data() != 0) {
407  LOG(WARNING) << "Receive Data Failed";
408  return Status::GENERIC_ERROR;
409  }
410 
411  if (net->recv_buff[m_sensorIndex].server_status() !=
412  payload::ServerStatus::REQUEST_ACCEPTED) {
413  LOG(WARNING) << "API execution on Target Failed";
414  return Status::GENERIC_ERROR;
415  }
416 
417  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
418 
419  // close the frame socket
421 
422  return status;
423 }
424 
426 NetworkDepthSensor::getAvailableModes(std::vector<uint8_t> &modes) {
427  using namespace aditof;
428 
429  Network *net = m_implData->handle.net;
430  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
431 
432  if (!net->isServer_Connected()) {
433  LOG(WARNING) << "Not connected to server";
434  return Status::UNREACHABLE;
435  }
436 
437  net->send_buff[m_sensorIndex].set_func_name("GetAvailableModes");
438  net->send_buff[m_sensorIndex].set_expect_reply(true);
439 
440  if (net->SendCommand() != 0) {
441  LOG(WARNING) << "Send Command Failed";
443  }
444 
445  if (net->recv_server_data() != 0) {
446  LOG(WARNING) << "Receive Data Failed";
447  return Status::GENERIC_ERROR;
448  }
449 
450  if (net->recv_buff[m_sensorIndex].server_status() !=
451  payload::ServerStatus::REQUEST_ACCEPTED) {
452  LOG(WARNING) << "API execution on Target Failed";
453  return Status::GENERIC_ERROR;
454  }
455 
456  // Cleanup array (if required) before filling it with the available types
457  if (modes.size() != 0) {
458  modes.clear();
459  }
460 
461  for (int i = 0; i < net->recv_buff[m_sensorIndex].int32_payload_size();
462  i++) {
463  modes.emplace_back(net->recv_buff[m_sensorIndex].int32_payload(i));
464  }
465 
466  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
467 
468  return status;
469 }
470 
474  using namespace aditof;
475  Network *net = m_implData->handle.net;
476  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
477 
478  if (!net->isServer_Connected()) {
479  LOG(WARNING) << "Not connected to server";
480  return Status::UNREACHABLE;
481  }
482 
483  net->send_buff[m_sensorIndex].set_func_name("GetModeDetails");
484  net->send_buff[m_sensorIndex].add_func_int32_param(mode);
485  net->send_buff[m_sensorIndex].set_expect_reply(true);
486 
487  if (net->SendCommand() != 0) {
488  LOG(WARNING) << "Send Command Failed";
490  }
491 
492  if (net->recv_server_data() != 0) {
493  LOG(WARNING) << "Receive Data Failed";
494  return Status::GENERIC_ERROR;
495  }
496 
497  if (net->recv_buff[m_sensorIndex].server_status() !=
498  payload::ServerStatus::REQUEST_ACCEPTED) {
499  LOG(WARNING) << "API execution on Target Failed";
500  return Status::GENERIC_ERROR;
501  }
502  details.modeNumber = mode;
504  .depth_sensor_mode_details()
505  .pixel_format_index();
507  .depth_sensor_mode_details()
508  .frame_width_in_bytes();
510  .depth_sensor_mode_details()
511  .frame_height_in_bytes();
513  .depth_sensor_mode_details()
514  .base_resolution_width();
516  .depth_sensor_mode_details()
517  .base_resolution_height();
518  details.metadataSize = net->recv_buff[m_sensorIndex]
519  .depth_sensor_mode_details()
520  .metadata_size();
521  details.isPCM =
522  net->recv_buff[m_sensorIndex].depth_sensor_mode_details().is_pcm();
523  details.numberOfPhases = net->recv_buff[m_sensorIndex]
524  .depth_sensor_mode_details()
525  .number_of_phases();
526  details.frameContent.clear();
527  for (int i = 0; i < net->recv_buff[m_sensorIndex]
528  .depth_sensor_mode_details()
529  .frame_content_size();
530  i++) {
531  details.frameContent.emplace_back(net->recv_buff[m_sensorIndex]
532  .depth_sensor_mode_details()
533  .frame_content(i));
534  }
535 
536  frame_size =
537  (details.baseResolutionWidth * details.baseResolutionHeight * 4) *
538  sizeof(uint16_t);
539 
540  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
541  return status;
542 }
543 
545  using namespace aditof;
546 
547  Network *net = m_implData->handle.net;
548  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
549 
550  if (!net->isServer_Connected()) {
551  LOG(WARNING) << "Not connected to server";
552  return Status::UNREACHABLE;
553  }
554 
555  net->send_buff[m_sensorIndex].set_func_name("SetModeByIndex");
556  net->send_buff[m_sensorIndex].add_func_int32_param(mode);
557  net->send_buff[m_sensorIndex].set_expect_reply(true);
558 
559  if (net->SendCommand() != 0) {
560  LOG(WARNING) << "Send Command Failed";
562  }
563 
564  if (net->recv_server_data() != 0) {
565  LOG(WARNING) << "Receive Data Failed";
566  return Status::GENERIC_ERROR;
567  }
568 
569  if (net->recv_buff[m_sensorIndex].server_status() !=
570  payload::ServerStatus::REQUEST_ACCEPTED) {
571  LOG(WARNING) << "API execution on Target Failed";
572  return Status::GENERIC_ERROR;
573  }
574 
575  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
576 
577  return status;
578 }
579 
582  using namespace aditof;
583 
584  Network *net = m_implData->handle.net;
585  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
586 
587  if (!net->isServer_Connected()) {
588  LOG(WARNING) << "Not connected to server";
589  return Status::UNREACHABLE;
590  }
591 
592  net->send_buff[m_sensorIndex].set_func_name("SetMode");
593  net->send_buff[m_sensorIndex].mutable_mode_details()->set_mode_number(
594  type.modeNumber);
596  .mutable_mode_details()
597  ->set_pixel_format_index(type.pixelFormatIndex);
599  .mutable_mode_details()
600  ->set_frame_width_in_bytes(type.frameWidthInBytes);
602  .mutable_mode_details()
603  ->set_frame_height_in_bytes(type.frameHeightInBytes);
605  .mutable_mode_details()
606  ->set_base_resolution_width(type.baseResolutionWidth);
608  .mutable_mode_details()
609  ->set_base_resolution_height(type.baseResolutionHeight);
610  net->send_buff[m_sensorIndex].mutable_mode_details()->set_is_pcm(
611  type.isPCM);
612  net->send_buff[m_sensorIndex].mutable_mode_details()->set_metadata_size(
613  type.metadataSize);
614  auto content = net->send_buff[m_sensorIndex].mutable_mode_details();
615  for (int i = 0; i < type.frameContent.size(); i++) {
616  content->add_frame_content(type.frameContent.at(i));
617  }
618 
619  net->send_buff[m_sensorIndex].set_expect_reply(true);
620 
621  frame_size = (type.baseResolutionWidth * type.baseResolutionHeight * 4) *
622  sizeof(uint16_t);
623 
624  if (net->SendCommand() != 0) {
625  LOG(WARNING) << "Send Command Failed";
627  }
628 
629  if (net->recv_server_data() != 0) {
630  LOG(WARNING) << "Receive Data Failed";
631  return Status::GENERIC_ERROR;
632  }
633 
634  if (net->recv_buff[m_sensorIndex].server_status() !=
635  payload::ServerStatus::REQUEST_ACCEPTED) {
636  LOG(WARNING) << "API execution on Target Failed";
637  return Status::GENERIC_ERROR;
638  }
639 
640  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
641 
642  if (status == Status::OK) {
643  m_implData->modeDetailsCache = type;
644  }
645 
646  return status;
647 }
648 
650  using namespace aditof;
651 
652  Network *net = m_implData->handle.net;
653  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
654 
655 #ifdef RECV_ASYNC
656  int ret = net->getFrame(buffer, frame_size);
657  if (ret == -1) {
658  return Status::GENERIC_ERROR;
659  }
660  return Status::OK;
661 
662 #else
663 
664  if (!net->isServer_Connected()) {
665  LOG(WARNING) << "Not connected to server";
666  return Status::UNREACHABLE;
667  }
668 
669  net->send_buff[m_sensorIndex].set_func_name("GetFrame");
670  net->send_buff[m_sensorIndex].set_expect_reply(true);
671 
672  if (net->SendCommand(static_cast<void *>(buffer)) != 0) {
673  LOG(WARNING) << "Send Command Failed";
675  }
676 
677  if (net->recv_server_data() != 0) {
678  LOG(WARNING) << "Receive Data Failed";
679  return Status::GENERIC_ERROR;
680  }
681 
682  int ret = net->getFrame(buffer, frame_size);
683  if (ret == -1) {
684  return Status::GENERIC_ERROR;
685  }
686 
687  if (net->recv_buff[m_sensorIndex].server_status() !=
688  payload::ServerStatus::REQUEST_ACCEPTED) {
689  LOG(WARNING) << "API execution on Target Failed";
690  return Status::GENERIC_ERROR;
691  }
692 
693  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
694  if (status != Status::OK) {
695  LOG(WARNING) << "getFrame() failed on target";
696  return status;
697  }
698 
699  return status;
700 
701 #endif
702 }
703 
705  std::vector<std::string> &controls) const {
706  using namespace aditof;
707 
708  Network *net = m_implData->handle.net;
709  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
710 
711  if (!net->isServer_Connected()) {
712  LOG(WARNING) << "Not connected to server";
713  return Status::UNREACHABLE;
714  }
715 
716  net->send_buff[m_sensorIndex].set_func_name("GetAvailableControls");
717  net->send_buff[m_sensorIndex].set_expect_reply(true);
718 
719  if (net->SendCommand() != 0) {
720  LOG(WARNING) << "Send Command Failed";
722  }
723 
724  if (net->recv_server_data() != 0) {
725  LOG(WARNING) << "Receive Data Failed";
726  return Status::GENERIC_ERROR;
727  }
728 
729  if (net->recv_buff[m_sensorIndex].server_status() !=
730  payload::ServerStatus::REQUEST_ACCEPTED) {
731  LOG(WARNING) << "API execution on Target Failed";
732  return Status::GENERIC_ERROR;
733  }
734 
735  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
736 
737  if (status == Status::OK) {
738  controls.clear();
739 
740  for (int i = 0;
741  i < net->recv_buff[m_sensorIndex].strings_payload_size(); i++) {
742  std::string controlName =
743  net->recv_buff[m_sensorIndex].strings_payload(i);
744  controls.push_back(controlName);
745  }
746  }
747 
748  return status;
749 }
750 
752  const std::string &value) {
753  using namespace aditof;
754 
755  Network *net = m_implData->handle.net;
756  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
757 
758  if (!net->isServer_Connected()) {
759  LOG(WARNING) << "Not connected to server";
760  return Status::UNREACHABLE;
761  }
762 
763  net->send_buff[m_sensorIndex].set_func_name("SetControl");
764  net->send_buff[m_sensorIndex].add_func_strings_param(control);
765  net->send_buff[m_sensorIndex].add_func_strings_param(value);
766  net->send_buff[m_sensorIndex].set_expect_reply(true);
767 
768  if (net->SendCommand() != 0) {
769  LOG(WARNING) << "Send Command Failed";
771  }
772 
773  if (net->recv_server_data() != 0) {
774  LOG(WARNING) << "Receive Data Failed";
775  return Status::GENERIC_ERROR;
776  }
777 
778  if (net->recv_buff[m_sensorIndex].server_status() !=
779  payload::ServerStatus::REQUEST_ACCEPTED) {
780  LOG(WARNING) << "API execution on Target Failed";
781  return Status::GENERIC_ERROR;
782  }
783 
784  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
785 
786  return status;
787 }
788 
790  std::string &value) const {
791  using namespace aditof;
792 
793  Network *net = m_implData->handle.net;
794  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
795 
796  if (!net->isServer_Connected()) {
797  LOG(WARNING) << "Not connected to server";
798  return Status::UNREACHABLE;
799  }
800 
801  net->send_buff[m_sensorIndex].set_func_name("GetControl");
802  net->send_buff[m_sensorIndex].add_func_strings_param(control);
803  net->send_buff[m_sensorIndex].set_expect_reply(true);
804 
805  if (net->SendCommand() != 0) {
806  LOG(WARNING) << "Send Command Failed";
808  }
809 
810  if (net->recv_server_data() != 0) {
811  LOG(WARNING) << "Receive Data Failed";
812  return Status::GENERIC_ERROR;
813  }
814 
815  if (net->recv_buff[m_sensorIndex].server_status() !=
816  payload::ServerStatus::REQUEST_ACCEPTED) {
817  LOG(WARNING) << "API execution on Target Failed";
818  return Status::GENERIC_ERROR;
819  }
820 
821  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
822 
823  if (status == Status::OK) {
824  value = net->recv_buff[m_sensorIndex].strings_payload(0);
825  }
826 
827  return status;
828 }
829 
832  details = m_sensorDetails;
833  return aditof::Status::OK;
834 }
835 
837  if (m_implData->opened) {
838  *handle = &m_implData->handle;
839  return aditof::Status::OK;
840  } else {
841  *handle = nullptr;
842  LOG(ERROR) << "Won't return the handle. Device hasn't been opened yet.";
844  }
845  return aditof::Status::OK;
846 }
847 
849  name = m_sensorName;
850  return aditof::Status::OK;
851 }
852 
855  LOG(INFO) << "Function used only on target!";
856  return aditof::Status::OK;
857 }
858 
860  uint16_t *data,
861  unsigned int usDelay) {
862  using namespace aditof;
863 
864  Network *net = m_implData->handle.net;
865  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
866 
867  if (!net->isServer_Connected()) {
868  LOG(WARNING) << "Not connected to server";
869  return Status::UNREACHABLE;
870  }
871 
872  net->send_buff[m_sensorIndex].set_func_name("Adsd3500ReadCmd");
873  net->send_buff[m_sensorIndex].add_func_int32_param(
874  static_cast<::google::int32>(cmd));
875  net->send_buff[m_sensorIndex].add_func_int32_param(
876  static_cast<::google::int32>(usDelay));
877  net->send_buff[m_sensorIndex].set_expect_reply(true);
878 
879  if (net->SendCommand() != 0) {
880  LOG(WARNING) << "Send Command Failed";
882  }
883 
884  if (net->recv_server_data() != 0) {
885  LOG(WARNING) << "Receive Data Failed";
886  return Status::GENERIC_ERROR;
887  }
888 
889  if (net->recv_buff[m_sensorIndex].server_status() !=
890  payload::ServerStatus::REQUEST_ACCEPTED) {
891  LOG(WARNING) << "API execution on Target Failed";
892  return Status::GENERIC_ERROR;
893  }
894 
895  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
896 
897  if (status == Status::OK) {
898  *data = static_cast<uint16_t>(
899  net->recv_buff[m_sensorIndex].int32_payload(0));
900  }
901 
902  return status;
903 }
904 
906  uint16_t data,
907  unsigned int usDelay) {
908  using namespace aditof;
909 
910  Network *net = m_implData->handle.net;
911  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
912 
913  if (!net->isServer_Connected()) {
914  LOG(WARNING) << "Not connected to server";
915  return Status::UNREACHABLE;
916  }
917 
918  net->send_buff[m_sensorIndex].set_func_name("Adsd3500WriteCmd");
919  net->send_buff[m_sensorIndex].add_func_int32_param(
920  static_cast<::google::int32>(cmd));
921  net->send_buff[m_sensorIndex].add_func_int32_param(
922  static_cast<::google::int32>(data));
923  net->send_buff[m_sensorIndex].add_func_int32_param(
924  static_cast<::google::int32>(usDelay));
925  net->send_buff[m_sensorIndex].set_expect_reply(true);
926 
927  if (net->SendCommand() != 0) {
928  LOG(WARNING) << "Send Command Failed";
930  }
931 
932  if (net->recv_server_data() != 0) {
933  LOG(WARNING) << "Receive Data Failed";
934  return Status::GENERIC_ERROR;
935  }
936 
937  if (net->recv_buff[m_sensorIndex].server_status() !=
938  payload::ServerStatus::REQUEST_ACCEPTED) {
939  LOG(WARNING) << "API execution on Target Failed";
940  return Status::GENERIC_ERROR;
941  }
942 
943  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
944 
945  return status;
946 }
947 
949  uint32_t cmd, uint8_t *readback_data, uint16_t payload_len) {
950  using namespace aditof;
951 
952  Network *net = m_implData->handle.net;
953  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
954 
955  if (!net->isServer_Connected()) {
956  LOG(WARNING) << "Not connected to server";
957  return Status::UNREACHABLE;
958  }
959 
960  net->send_buff[m_sensorIndex].set_func_name("Adsd3500ReadPayloadCmd");
961  net->send_buff[m_sensorIndex].add_func_int32_param(
962  static_cast<::google::int32>(cmd));
963  net->send_buff[m_sensorIndex].add_func_int32_param(
964  static_cast<::google::int32>(payload_len));
965  net->send_buff[m_sensorIndex].add_func_bytes_param(readback_data,
966  4 * sizeof(uint8_t));
967  net->send_buff[m_sensorIndex].set_expect_reply(true);
968 
969  if (net->SendCommand() != 0) {
970  LOG(WARNING) << "Send Command Failed";
972  }
973 
974  if (net->recv_server_data() != 0) {
975  LOG(WARNING) << "Receive Data Failed";
976  return Status::GENERIC_ERROR;
977  }
978 
979  if (net->recv_buff[m_sensorIndex].server_status() !=
980  payload::ServerStatus::REQUEST_ACCEPTED) {
981  LOG(WARNING) << "API execution on Target Failed";
982  return Status::GENERIC_ERROR;
983  }
984 
985  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
986 
987  if (status == Status::OK) {
988  memcpy(readback_data,
989  net->recv_buff[m_sensorIndex].bytes_payload(0).c_str(),
990  net->recv_buff[m_sensorIndex].bytes_payload(0).length());
991  }
992 
993  return status;
994 }
995 
997  uint16_t payload_len) {
998  using namespace aditof;
999 
1000  Network *net = m_implData->handle.net;
1001  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
1002 
1003  if (!net->isServer_Connected()) {
1004  LOG(WARNING) << "Not connected to server";
1005  return Status::UNREACHABLE;
1006  }
1007 
1008  net->send_buff[m_sensorIndex].set_func_name("Adsd3500ReadPayload");
1009  net->send_buff[m_sensorIndex].add_func_int32_param(
1010  static_cast<::google::int32>(payload_len));
1011  net->send_buff[m_sensorIndex].set_expect_reply(true);
1012 
1013  if (net->SendCommand() != 0) {
1014  LOG(WARNING) << "Send Command Failed";
1015  return Status::INVALID_ARGUMENT;
1016  }
1017 
1018  if (net->recv_server_data() != 0) {
1019  LOG(WARNING) << "Receive Data Failed";
1020  return Status::GENERIC_ERROR;
1021  }
1022 
1023  if (net->recv_buff[m_sensorIndex].server_status() !=
1024  payload::ServerStatus::REQUEST_ACCEPTED) {
1025  LOG(WARNING) << "API execution on Target Failed";
1026  return Status::GENERIC_ERROR;
1027  }
1028 
1029  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
1030 
1031  if (status == Status::OK) {
1032  memcpy(payload, net->recv_buff[m_sensorIndex].bytes_payload(0).c_str(),
1033  net->recv_buff[m_sensorIndex].bytes_payload(0).length());
1034  }
1035 
1036  return status;
1037 }
1038 
1040 NetworkDepthSensor::adsd3500_write_payload_cmd(uint32_t cmd, uint8_t *payload,
1041  uint16_t payload_len) {
1042  using namespace aditof;
1043 
1044  Network *net = m_implData->handle.net;
1045  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
1046 
1047  if (!net->isServer_Connected()) {
1048  LOG(WARNING) << "Not connected to server";
1049  return Status::UNREACHABLE;
1050  }
1051 
1052  net->send_buff[m_sensorIndex].set_func_name("Adsd3500WritePayloadCmd");
1053  net->send_buff[m_sensorIndex].add_func_int32_param(
1054  static_cast<::google::int32>(cmd));
1055  net->send_buff[m_sensorIndex].add_func_int32_param(
1056  static_cast<::google::int32>(payload_len));
1057  net->send_buff[m_sensorIndex].add_func_bytes_param(payload, payload_len);
1058  net->send_buff[m_sensorIndex].set_expect_reply(true);
1059 
1060  if (net->SendCommand() != 0) {
1061  LOG(WARNING) << "Send Command Failed";
1062  return Status::INVALID_ARGUMENT;
1063  }
1064 
1065  if (net->recv_server_data() != 0) {
1066  LOG(WARNING) << "Receive Data Failed";
1067  return Status::GENERIC_ERROR;
1068  }
1069 
1070  if (net->recv_buff[m_sensorIndex].server_status() !=
1071  payload::ServerStatus::REQUEST_ACCEPTED) {
1072  LOG(WARNING) << "API execution on Target Failed";
1073  return Status::GENERIC_ERROR;
1074  }
1075 
1076  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
1077 
1078  return status;
1079 }
1080 
1083  uint16_t payload_len) {
1084  using namespace aditof;
1085 
1086  Network *net = m_implData->handle.net;
1087  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
1088 
1089  if (!net->isServer_Connected()) {
1090  LOG(WARNING) << "Not connected to server";
1091  return Status::UNREACHABLE;
1092  }
1093 
1094  net->send_buff[m_sensorIndex].set_func_name("Adsd3500WritePayload");
1095  net->send_buff[m_sensorIndex].add_func_int32_param(
1096  static_cast<::google::int32>(payload_len));
1097  net->send_buff[m_sensorIndex].add_func_bytes_param(payload, payload_len);
1098  net->send_buff[m_sensorIndex].set_expect_reply(true);
1099 
1100  if (net->SendCommand() != 0) {
1101  LOG(WARNING) << "Send Command Failed";
1102  return Status::INVALID_ARGUMENT;
1103  }
1104 
1105  if (net->recv_server_data() != 0) {
1106  LOG(WARNING) << "Receive Data Failed";
1107  return Status::GENERIC_ERROR;
1108  }
1109 
1110  if (net->recv_buff[m_sensorIndex].server_status() !=
1111  payload::ServerStatus::REQUEST_ACCEPTED) {
1112  LOG(WARNING) << "API execution on Target Failed";
1113  return Status::GENERIC_ERROR;
1114  }
1115 
1116  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
1117 
1118  return status;
1119 }
1120 
1122  using namespace aditof;
1123 
1124  Network *net = m_implData->handle.net;
1125  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
1126 
1127  if (!net->isServer_Connected()) {
1128  LOG(WARNING) << "Not connected to server";
1129  return Status::UNREACHABLE;
1130  }
1131 
1132  net->send_buff[m_sensorIndex].set_func_name("Adsd3500Reset");
1133  net->send_buff[m_sensorIndex].set_expect_reply(true);
1134 
1135  if (net->SendCommand() != 0) {
1136  LOG(WARNING) << "Send Command Failed";
1137  return Status::INVALID_ARGUMENT;
1138  }
1139 
1140  if (net->recv_server_data() != 0) {
1141  LOG(WARNING) << "Receive Data Failed";
1142  return Status::GENERIC_ERROR;
1143  }
1144 
1145  if (net->recv_buff[m_sensorIndex].server_status() !=
1146  payload::ServerStatus::REQUEST_ACCEPTED) {
1147  LOG(WARNING) << "API execution on Target Failed";
1148  return Status::GENERIC_ERROR;
1149  }
1150 
1151  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
1152 
1153  return status;
1154 }
1155 
1158  m_interruptCallbackMap.insert({&cb, cb});
1159  return aditof::Status::OK;
1160 }
1161 
1164 
1165  m_interruptCallbackMap.erase(&cb);
1166 
1167  return aditof::Status::OK;
1168 }
1169 
1171  int &imagerStatus) {
1172  using namespace aditof;
1173 
1174  Network *net = m_implData->handle.net;
1175  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
1176 
1177  if (!net->isServer_Connected()) {
1178  LOG(WARNING) << "Not connected to server";
1179  return Status::UNREACHABLE;
1180  }
1181 
1182  net->send_buff[m_sensorIndex].set_func_name("Adsd3500GetStatus");
1183  net->send_buff[m_sensorIndex].set_expect_reply(true);
1184 
1185  if (net->SendCommand() != 0) {
1186  LOG(WARNING) << "Send Command Failed";
1187  return Status::INVALID_ARGUMENT;
1188  }
1189 
1190  if (net->recv_server_data() != 0) {
1191  LOG(WARNING) << "Receive Data Failed";
1192  return Status::GENERIC_ERROR;
1193  }
1194 
1195  if (net->recv_buff[m_sensorIndex].server_status() !=
1196  payload::ServerStatus::REQUEST_ACCEPTED) {
1197  LOG(WARNING) << "API execution on Target Failed";
1198  return Status::GENERIC_ERROR;
1199  }
1200 
1201  chipStatus = net->recv_buff[m_sensorIndex].int32_payload(0);
1202  imagerStatus = net->recv_buff[m_sensorIndex].int32_payload(1);
1203 
1204  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
1205 
1206  return status;
1207 }
1208 
1210  uint8_t *iniFile, uint16_t iniFileLength, uint8_t *calData,
1211  uint16_t calDataLength) {
1212  using namespace aditof;
1213 
1214  Network *net = m_implData->handle.net;
1215  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
1216 
1217  if (!net->isServer_Connected()) {
1218  LOG(WARNING) << "Not connected to server";
1219  return Status::UNREACHABLE;
1220  }
1221 
1222  net->send_buff[m_sensorIndex].set_func_name("InitTargetDepthCompute");
1223  net->send_buff[m_sensorIndex].add_func_int32_param(
1224  static_cast<::google::int32>(iniFileLength));
1225  net->send_buff[m_sensorIndex].add_func_int32_param(
1226  static_cast<::google::int32>(calDataLength));
1227  net->send_buff[m_sensorIndex].add_func_bytes_param(iniFile, iniFileLength);
1228  net->send_buff[m_sensorIndex].add_func_bytes_param(calData, calDataLength);
1229  net->send_buff[m_sensorIndex].set_expect_reply(true);
1230 
1231  if (net->SendCommand() != 0) {
1232  LOG(WARNING) << "Send Command Failed";
1233  return Status::INVALID_ARGUMENT;
1234  }
1235 
1236  if (net->recv_server_data() != 0) {
1237  LOG(WARNING) << "Receive Data Failed";
1238  return Status::GENERIC_ERROR;
1239  }
1240 
1241  if (net->recv_buff[m_sensorIndex].server_status() !=
1242  payload::ServerStatus::REQUEST_ACCEPTED) {
1243  LOG(WARNING) << "API execution on Target Failed";
1244  return Status::GENERIC_ERROR;
1245  }
1246 
1247  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
1248 
1249  return status;
1250 }
1251 
1253  using namespace std::chrono;
1254 
1255  while (!m_stopServerCheck) {
1256  // get latest timestamp from Network object
1257  steady_clock::time_point latestActivityTimestamp =
1258  m_implData->handle.net->getLatestActivityTimestamp();
1259 
1260  // get current timestamp
1261  steady_clock::time_point now = steady_clock::now();
1262 
1263  // decide if it is required to check for server updates
1264  duration<double> inactivityDuration =
1265  duration_cast<duration<double>>(now - latestActivityTimestamp);
1266  if (inactivityDuration.count() > 1.0) {
1267  // check server for interrupts
1268  std::unique_lock<std::mutex> mutex_lock(
1269  m_implData->handle.net_mutex);
1270  if (m_implData->handle.net->isServer_Connected()) {
1271  m_implData->cb();
1272  } else {
1273  m_stopServerCheck = true;
1274  break;
1275  }
1276  }
1277  // go back to sleep
1278  std::this_thread::sleep_for(std::chrono::milliseconds(1000));
1279  }
1280 }
1281 
1284  using namespace aditof;
1285 
1286  Network *net = m_implData->handle.net;
1287  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
1288 
1289  if (!net->isServer_Connected()) {
1290  LOG(WARNING) << "Not connected to server";
1291  return Status::UNREACHABLE;
1292  }
1293 
1294  net->send_buff[m_sensorIndex].set_func_name("SetSensorConfiguration");
1295  net->send_buff[m_sensorIndex].add_func_strings_param(sensorConf);
1296  net->send_buff[m_sensorIndex].set_expect_reply(true);
1297 
1298  if (net->SendCommand() != 0) {
1299  LOG(WARNING) << "Send Command Failed";
1300  return Status::INVALID_ARGUMENT;
1301  }
1302 
1303  if (net->recv_server_data() != 0) {
1304  LOG(WARNING) << "Receive Data Failed";
1305  return Status::GENERIC_ERROR;
1306  }
1307 
1308  if (net->recv_buff[m_sensorIndex].server_status() !=
1309  payload::ServerStatus::REQUEST_ACCEPTED) {
1310  LOG(WARNING) << "API execution on Target Failed";
1311  return Status::GENERIC_ERROR;
1312  }
1313 
1314  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
1315 
1316  return status;
1317 }
1318 
1321 
1322  using namespace aditof;
1323 
1324  Network *net = m_implData->handle.net;
1325  std::unique_lock<std::mutex> mutex_lock(m_implData->handle.net_mutex);
1326 
1327  if (!net->isServer_Connected()) {
1328  LOG(WARNING) << "Not connected to server";
1329  return Status::UNREACHABLE;
1330  }
1331 
1332  net->send_buff[m_sensorIndex].set_func_name("GetIniArray");
1333  net->send_buff[m_sensorIndex].add_func_int32_param(
1334  static_cast<::google::int32>(mode));
1335  net->send_buff[m_sensorIndex].set_expect_reply(true);
1336 
1337  if (net->SendCommand() != 0) {
1338  LOG(WARNING) << "Send Command Failed";
1339  return Status::INVALID_ARGUMENT;
1340  }
1341 
1342  if (net->recv_server_data() != 0) {
1343  LOG(WARNING) << "Receive Data Failed";
1344  return Status::GENERIC_ERROR;
1345  }
1346 
1347  if (net->recv_buff[m_sensorIndex].server_status() !=
1348  payload::ServerStatus::REQUEST_ACCEPTED) {
1349  LOG(WARNING) << "API execution on Target Failed";
1350  return Status::GENERIC_ERROR;
1351  }
1352 
1353  Status status = static_cast<Status>(net->recv_buff[m_sensorIndex].status());
1354 
1355  if (status == Status::OK) {
1356  iniStr = net->recv_buff[m_sensorIndex].strings_payload(0);
1357  }
1358 
1359  return status;
1360 }
aditof::DepthSensorModeDetails::isPCM
int isPCM
set to true if the mode is PCM
Definition: sensor_definitions.h:170
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
Network::closeConnectionFrameSocket
void closeConnectionFrameSocket()
closeConnectionFrameSocket() - APi to close the frame socket connection
Definition: network.cpp:585
INFO
const int INFO
Definition: log_severity.h:59
name
GLuint const GLchar * name
Definition: glcorearb.h:3055
aditof::DepthSensorModeDetails::frameContent
std::vector< std::string > frameContent
Stores the content of each frame.
Definition: sensor_definitions.h:130
aditof::DepthSensorModeDetails::modeNumber
uint8_t modeNumber
Number associated with the mode.
Definition: sensor_definitions.h:125
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
aditof::DepthSensorModeDetails::frameHeightInBytes
int frameHeightInBytes
Driver height, can be used for both chipRaw and imagerRaw.
Definition: sensor_definitions.h:150
NetworkDepthSensor::ImplData::handle
NetworkHandle handle
Definition: network_depth_sensor.cpp:50
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::DepthSensorModeDetails::baseResolutionHeight
int baseResolutionHeight
Processed data height.
Definition: sensor_definitions.h:160
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
ERROR
const int ERROR
Definition: log_severity.h:60
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
CalibrationData::cache
uint16_t * cache
Definition: network_depth_sensor.cpp:47
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
CalibrationData::gain
float gain
Definition: network_depth_sensor.cpp:45
mode
GLenum mode
Definition: glcorearb.h:2764
aditof::ConnectionType::NETWORK
@ NETWORK
connects to target via Network
log.h
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
aditof::Status::UNAVAILABLE
@ UNAVAILABLE
The requested action or resource is unavailable.
WARNING
const int WARNING
Definition: log_severity.h:59
aditof::Adsd3500Status
Adsd3500Status
Status of the ADSD3500 sensor.
Definition: status_definitions.h:61
Network::FrameSocketConnection
void FrameSocketConnection(std::string &ip)
FrameSocketConnection() - APi to establish Frame Socket connection.
Definition: network.cpp:599
Network::ServerConnect
int ServerConnect(const std::string &ip)
Definition: network.cpp:150
NetworkDepthSensor::getName
virtual aditof::Status getName(std::string &name) const override
Get the name of the sensor.
Definition: network_depth_sensor.cpp:848
aditof::DepthSensorModeDetails::metadataSize
int metadataSize
Stores the size of metadata.
Definition: sensor_definitions.h:165
NetworkDepthSensor::ImplData::modeDetailsCache
aditof::DepthSensorModeDetails modeDetailsCache
Definition: network_depth_sensor.cpp:52
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
aditof::SensorDetails::id
std::string id
The sensor identification data to be used to differentiate between sensors. When on target,...
Definition: sensor_definitions.h:55
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
aditof
Namespace aditof.
Definition: adsd_errs.h:40
Network::recv_server_data
int recv_server_data()
recv_server_data() - APi to receive data from server
Definition: network.cpp:326
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
aditof::DepthSensorModeDetails::pixelFormatIndex
int pixelFormatIndex
Index of two possbile values sensor values (8bit, 12/16bit)
Definition: sensor_definitions.h:140
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
google::protobuf::util::error::OK
@ OK
Definition: status.h:47
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
NetworkDepthSensor::ImplData::opened
bool opened
Definition: network_depth_sensor.cpp:54
Network::isServer_Connected
bool isServer_Connected()
isServer_Connected() - APi to check if server is connected successfully
Definition: network.cpp:97
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
m_connectionList
std::vector< std::string > m_connectionList
Definition: network.cpp:87
NetworkDepthSensor::m_stopServerCheck
bool m_stopServerCheck
Definition: network_depth_sensor.h:120
Network::send_buff
static payload::ClientRequest send_buff[MAX_CAMERA_NUM]
Definition: network.h:90
google::protobuf::util::error::INVALID_ARGUMENT
@ INVALID_ARGUMENT
Definition: status.h:50
CalibrationData
Definition: network_depth_sensor.cpp:43
aditof::Status
Status
Status of any operation that the TOF sdk performs.
Definition: status_definitions.h:48
Network
Definition: network.h:50
i
int i
Definition: gmock-matchers_test.cc:764
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
aditof::DepthSensorModeDetails::baseResolutionWidth
int baseResolutionWidth
Processed data witdh.
Definition: sensor_definitions.h:155
LOG
#define LOG(x)
Definition: sdk/include/aditof/log.h:72
google::int32
int32_t int32
Definition: sdk/include/aditof/log.h:54
aditof::Status::OK
@ OK
Success.
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
Network::InterruptNotificationCallback
std::function< void(void)> InterruptNotificationCallback
Definition: network.h:52
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::ImplData::ip
std::string ip
Definition: network_depth_sensor.cpp:51
NetworkDepthSensor::ImplData::cb
Network::InterruptNotificationCallback cb
Definition: network_depth_sensor.cpp:55
Network::getFrame
int32_t getFrame(uint16_t *buffer, uint32_t buf_size)
getFrame() - APi to get frame in Async
Definition: network.cpp:568
network.h
NetworkDepthSensor::m_implData
std::unique_ptr< ImplData > m_implData
Definition: network_depth_sensor.h:115
Network::SendCommand
int SendCommand(void *rawPayload=nullptr)
Definition: network.cpp:280
CalibrationData::offset
float offset
Definition: network_depth_sensor.cpp:46
CalibrationData::mode
std::string mode
Definition: network_depth_sensor.cpp:44
NetworkDepthSensor::~NetworkDepthSensor
~NetworkDepthSensor()
Definition: network_depth_sensor.cpp:124
aditof::DepthSensorModeDetails::frameWidthInBytes
int frameWidthInBytes
Driver width, can be used for both chipRaw and imagerRaw.
Definition: sensor_definitions.h:145
network_depth_sensor.h
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
aditof::DepthSensorModeDetails::numberOfPhases
uint8_t numberOfPhases
Number of phases.
Definition: sensor_definitions.h:135
aditof::SensorDetails::connectionType
ConnectionType connectionType
The type of connection with the sensor.
Definition: sensor_definitions.h:60
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
Network::recv_buff
static payload::ServerResponse recv_buff[MAX_CAMERA_NUM]
Definition: network.h:91
NetworkDepthSensor::m_interruptCallbackMap
std::unordered_map< void *, aditof::SensorInterruptCallback > m_interruptCallbackMap
Definition: network_depth_sensor.h:119
false
#define false
Definition: cJSON.c:70
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::ImplData::calibration_cache
std::unordered_map< std::string, CalibrationData > calibration_cache
Definition: network_depth_sensor.cpp:53
it
MapIter it
Definition: php/ext/google/protobuf/map.c:205
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
NetworkHandle
Definition: network.h:45
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